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 yCTrace(CONTROLBOARD, "Handling IImpedance message");
35 if (!rpc_IImpedance) {
36 yCError(CONTROLBOARD, "I do not have a valid interface");
37 *ok = false;
38 return;
39 }
40
41 int code = cmd.get(0).asVocab32();
42 *ok = false;
43 switch (code) {
44 case VOCAB_SET: {
45 yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_SET command");
46 switch (cmd.get(2).asVocab32()) {
47 case VOCAB_IMP_PARAM: {
48 Bottle* b = cmd.get(4).asList();
49 if (b != nullptr) {
50 double stiff = b->get(0).asFloat64();
51 double damp = b->get(1).asFloat64();
53 *rec = true;
54 }
55 } break;
56 case VOCAB_IMP_OFFSET: {
57 Bottle* b = cmd.get(4).asList();
58 if (b != nullptr) {
59 double offs = b->get(0).asFloat64();
61 *rec = true;
62 }
63 } break;
64 }
65 } break;
66 case VOCAB_GET: {
67 double stiff = 0;
68 double damp = 0;
69 double offs = 0;
70 yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_GET command");
71
72 response.addVocab32(VOCAB_IS);
73 response.add(cmd.get(1));
74 switch (cmd.get(2).asVocab32()) {
75 case VOCAB_IMP_PARAM: {
76 *ok = rpc_IImpedance->getImpedance(cmd.get(3).asInt32(), &stiff, &damp);
77 Bottle& b = response.addList();
80 *rec = true;
81 } break;
82 case VOCAB_IMP_OFFSET: {
84 Bottle& b = response.addList();
86 *rec = true;
87 } break;
88 case VOCAB_LIMITS: {
89 double min_stiff = 0;
90 double max_stiff = 0;
91 double min_damp = 0;
92 double max_damp = 0;
93 *ok = rpc_IImpedance->getCurrentImpedanceLimit(cmd.get(3).asInt32(), &min_stiff, &max_stiff, &min_damp, &max_damp);
94 Bottle& b = response.addList();
95 b.addFloat64(min_stiff);
96 b.addFloat64(max_stiff);
97 b.addFloat64(min_damp);
98 b.addFloat64(max_damp);
99 *rec = true;
100 } break;
101 }
102 }
104 appendTimeStamp(response, lastRpcStamp);
105 break; // case VOCAB_GET
106 default:
107 {
108 *rec = false;
109 } break;
110 }
111}
112
114 yarp::os::Bottle& response,
115 bool* rec,
116 bool* ok)
117{
118 //handle here messages about IControlMode interface
119 int code = cmd.get(0).asVocab32();
120 *ok = true;
121 *rec = true; //or false
122
123 switch (code)
124 {
125 case VOCAB_GET:
126 yCTrace(CONTROLBOARD, "GET command");
127
128 int method = cmd.get(2).asVocab32();
129
130 switch (method)
131 {
133 yCTrace(CONTROLBOARD, "getJointFault");
134 int axis = cmd.get(3).asInt32();
135 int faultcode=0;
136 std::string faultmessage;
137 if (rpc_IJointFault)
138 {
140 *rec = true;
141 }
142 response.addVocab32(VOCAB_IS);
143 response.addInt32(faultcode);
144 response.addString(faultmessage);
145
146 yCTrace(CONTROLBOARD, "Returning %d %s", faultcode, faultmessage.c_str());
147 *rec = true;
148 break;
149 }
150
151 break;
152 }
153}
154
156 yarp::os::Bottle& response,
157 bool* rec,
158 bool* ok)
159{
160 yCTrace(CONTROLBOARD, "Handling IControlMode message");
161 if (!(rpc_iCtrlMode)) {
162 yCError(CONTROLBOARD, "I do not have a valid iControlMode interface");
163 *ok = false;
164 return;
165 }
166
167 //handle here messages about IControlMode interface
168 int code = cmd.get(0).asVocab32();
169 *ok = true;
170 *rec = true; //or false
171
172 switch (code) {
173 case VOCAB_SET: {
174 yCTrace(CONTROLBOARD, "handleControlModeMsg::VOCAB_SET command");
175
176 int method = cmd.get(2).asVocab32();
177
178 switch (method) {
180 int axis = cmd.get(3).asInt32();
181 yCTrace(CONTROLBOARD) << "got VOCAB_CM_CONTROL_MODE";
182 if (rpc_iCtrlMode) {
184 } else {
185 yCError(CONTROLBOARD) << "Unable to handle setControlMode request! This should not happen!";
186 *rec = false;
187 }
188 } break;
189
191 int n_joints = cmd.get(3).asInt32();
192 Bottle& jList = *(cmd.get(4).asList());
193 Bottle& modeList = *(cmd.get(5).asList());
194
195 int* js = new int[n_joints];
196 int* modes = new int[n_joints];
197
198 for (int i = 0; i < n_joints; i++) {
199 js[i] = jList.get(i).asInt32();
200 }
201
202 for (int i = 0; i < n_joints; i++) {
203 modes[i] = modeList.get(i).asVocab32();
204 }
205 if (rpc_iCtrlMode) {
206 *ok = rpc_iCtrlMode->setControlModes(n_joints, js, modes);
207 } else {
208 *rec = false;
209 *ok = false;
210 }
211 delete[] js;
212 delete[] modes;
213 } break;
214
217 modeList = cmd.get(3).asList();
218
219 if (modeList->size() != controlledJoints) {
220 yCError(CONTROLBOARD, "received an invalid setControlMode message. Size of vector doesn´t match the number of controlled joints");
221 *ok = false;
222 break;
223 }
224 int* modes = new int[controlledJoints];
225 for (size_t i = 0; i < controlledJoints; i++) {
226 modes[i] = modeList->get(i).asVocab32();
227 }
228 if (rpc_iCtrlMode) {
230 } else {
231 *rec = false;
232 *ok = false;
233 }
234 delete[] modes;
235 } break;
236
237 default:
238 {
239 // if I´m here, someone is probably sending command using the old interface.
240 // try to be compatible as much as I can
241
242 yCError(CONTROLBOARD) << " Error, received a set control mode message using a legacy version, trying to be handle the message anyway "
243 << " but please update your client to be compatible with the IControlMode interface";
244
245 yCTrace(CONTROLBOARD) << " cmd.get(4).asVocab32() is " << Vocab32::decode(cmd.get(4).asVocab32());
246 int axis = cmd.get(3).asInt32();
247
248 switch (cmd.get(4).asVocab32()) {
250 if (rpc_iCtrlMode) {
252 }
253 break;
254
256 if (rpc_iCtrlMode) {
258 } else {
259 *rec = false;
260 *ok = false;
261 }
262 break;
263
264
266 if (rpc_iCtrlMode) {
268 }
269 break;
270
271 case VOCAB_CM_TORQUE:
272 if (rpc_iCtrlMode) {
274 }
275 break;
276
278 yCError(CONTROLBOARD) << "The 'impedancePosition' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_POSITION) instead";
279 break;
280
282 yCError(CONTROLBOARD) << "The 'impedanceVelocity' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_VELOCITY) instead";
283 break;
284
285 case VOCAB_CM_PWM:
286 if (rpc_iCtrlMode) {
288 } else {
289 *rec = false;
290 *ok = false;
291 }
292 break;
293
294 case VOCAB_CM_CURRENT:
295 if (rpc_iCtrlMode) {
297 } else {
298 *rec = false;
299 *ok = false;
300 }
301 break;
302
303 case VOCAB_CM_MIXED:
304 if (rpc_iCtrlMode) {
306 } else {
307 *rec = false;
308 *ok = false;
309 }
310 break;
311
313 if (rpc_iCtrlMode) {
315 } else {
316 *rec = false;
317 *ok = false;
318 }
319 break;
320
321 default:
322 yCError(CONTROLBOARD, "SET unknown controlMode : %s ", cmd.toString().c_str());
323 *ok = false;
324 *rec = false;
325 break;
326 }
327 } break; // close default case
328 }
329 } break; // close SET case
330
331 case VOCAB_GET: {
332 yCTrace(CONTROLBOARD, "GET command");
333
334 int method = cmd.get(2).asVocab32();
335
336 switch (method) {
337
339 yCTrace(CONTROLBOARD, "getControlModes");
340 int* p = new int[controlledJoints];
341 for (size_t i = 0; i < controlledJoints; ++i) {
342 p[i] = -1;
343 }
344 if (rpc_iCtrlMode) {
346 }
347
348 response.addVocab32(VOCAB_IS);
350
351 Bottle& b = response.addList();
352 for (size_t i = 0; i < controlledJoints; i++) {
353 b.addVocab32(p[i]);
354 }
355 delete[] p;
356
357 *rec = true;
358 } break;
359
361 yCTrace(CONTROLBOARD, "getControlMode");
362
363 int p = -1;
364 int axis = cmd.get(3).asInt32();
365 if (rpc_iCtrlMode) {
367 }
368
369 response.addVocab32(VOCAB_IS);
370 response.addInt32(axis);
371 response.addVocab32(p);
372
373 yCTrace(CONTROLBOARD, "Returning %d", p);
374 *rec = true;
375 } break;
376
378 yCTrace(CONTROLBOARD, "getControlMode group");
379
380 int n_joints = cmd.get(3).asInt32();
381 Bottle& lIn = *(cmd.get(4).asList());
382
383 int* js = new int[n_joints];
384 int* modes = new int[n_joints];
385 for (int i = 0; i < n_joints; i++) {
386 js[i] = lIn.get(i).asInt32();
387 modes[i] = -1;
388 }
389 if (rpc_iCtrlMode) {
390 *ok = rpc_iCtrlMode->getControlModes(n_joints, js, modes);
391 } else {
392 *rec = false;
393 *ok = false;
394 }
395
396 response.addVocab32(VOCAB_IS);
398 Bottle& b = response.addList();
399 for (int i = 0; i < n_joints; i++) {
400 b.addVocab32(modes[i]);
401 }
402
403 delete[] js;
404 delete[] modes;
405
406 *rec = true;
407 } break;
408
409 default:
410 yCError(CONTROLBOARD, "received a GET ICONTROLMODE command not understood");
411 break;
412 }
413 }
414
416 appendTimeStamp(response, lastRpcStamp);
417 break; // case VOCAB_GET
418
419 default:
420 {
421 *rec = false;
422 } break;
423 }
424}
425
426
428 yarp::os::Bottle& response,
429 bool* rec,
430 bool* ok)
431{
432 yCTrace(CONTROLBOARD, "Handling ITorqueControl message");
433
434 if (!rpc_ITorque) {
435 yCError(CONTROLBOARD, "Error, I do not have a valid ITorque interface");
436 *ok = false;
437 return;
438 }
439
440 int code = cmd.get(0).asVocab32();
441 switch (code) {
442 case VOCAB_SET: {
443 *rec = true;
444 yCTrace(CONTROLBOARD, "set command received");
445
446 switch (cmd.get(2).asVocab32()) {
447 case VOCAB_REF: {
448 *ok = rpc_ITorque->setRefTorque(cmd.get(3).asInt32(), cmd.get(4).asFloat64());
449 } break;
450
451 case VOCAB_MOTOR_PARAMS: {
453 int joint = cmd.get(3).asInt32();
454 Bottle* b = cmd.get(4).asList();
455
456 if (b == nullptr) {
457 break;
458 }
459
460 if (b->size() != 9) {
461 yCError(CONTROLBOARD, "received a SET VOCAB_MOTOR_PARAMS command not understood, size != 9");
462 break;
463 }
464
465 params.bemf = b->get(0).asFloat64();
466 params.bemf_scale = b->get(1).asFloat64();
467 params.ktau = b->get(2).asFloat64();
468 params.ktau_scale = b->get(3).asFloat64();
469 params.viscousPos = b->get(4).asFloat64();
470 params.viscousNeg = b->get(5).asFloat64();
471 params.coulombPos = b->get(6).asFloat64();
472 params.coulombNeg = b->get(7).asFloat64();
473 params.velocityThres = b->get(8).asFloat64();
474
475 *ok = rpc_ITorque->setMotorTorqueParams(joint, params);
476 } break;
477
478 case VOCAB_REFS: {
479 Bottle* b = cmd.get(3).asList();
480 if (b == nullptr) {
481 break;
482 }
483
484 const size_t njs = b->size();
485 if (njs == controlledJoints) {
486 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
487 for (size_t i = 0; i < njs; i++) {
488 p[i] = b->get(i).asFloat64();
489 }
490 *ok = rpc_ITorque->setRefTorques(p);
491 delete[] p;
492 }
493 } break;
494
495 case VOCAB_TORQUE_MODE: {
496 if (rpc_iCtrlMode) {
497 int* modes = new int[controlledJoints];
498 for (size_t i = 0; i < controlledJoints; i++) {
500 }
502 delete[] modes;
503 } else {
504 *ok = false;
505 }
506 } break;
507 }
508 } break;
509
510 case VOCAB_GET: {
511 *rec = true;
512 yCTrace(CONTROLBOARD, "get command received");
513 double dtmp = 0.0;
514 double dtmp2 = 0.0;
515 response.addVocab32(VOCAB_IS);
516 response.add(cmd.get(1));
517
518 switch (cmd.get(2).asVocab32()) {
519
520 case VOCAB_TRQ: {
521 *ok = rpc_ITorque->getTorque(cmd.get(3).asInt32(), &dtmp);
522 response.addFloat64(dtmp);
523 } break;
524
525 case VOCAB_MOTOR_PARAMS: {
527 int joint = cmd.get(3).asInt32();
528
529 // get the data
530 *ok = rpc_ITorque->getMotorTorqueParams(joint, &params);
531
532 // convert it back to yarp message
533 Bottle& b = response.addList();
534
535 b.addFloat64(params.bemf);
536 b.addFloat64(params.bemf_scale);
537 b.addFloat64(params.ktau);
538 b.addFloat64(params.ktau_scale);
539 b.addFloat64(params.viscousPos);
540 b.addFloat64(params.viscousNeg);
541 b.addFloat64(params.coulombPos);
542 b.addFloat64(params.coulombNeg);
543 b.addFloat64(params.velocityThres);
544 } break;
545
546 case VOCAB_RANGE: {
547 *ok = rpc_ITorque->getTorqueRange(cmd.get(3).asInt32(), &dtmp, &dtmp2);
548 response.addFloat64(dtmp);
549 response.addFloat64(dtmp2);
550 } break;
551
552 case VOCAB_TRQS: {
553 auto* p = new double[controlledJoints];
554 *ok = rpc_ITorque->getTorques(p);
555 Bottle& b = response.addList();
556 for (size_t i = 0; i < controlledJoints; i++) {
557 b.addFloat64(p[i]);
558 }
559 delete[] p;
560 } break;
561
562 case VOCAB_RANGES: {
563 auto* p1 = new double[controlledJoints];
564 auto* p2 = new double[controlledJoints];
566 Bottle& b1 = response.addList();
567 for (size_t i = 0; i < controlledJoints; i++) {
568 b1.addFloat64(p1[i]);
569 }
570 Bottle& b2 = response.addList();
571 for (size_t i = 0; i < controlledJoints; i++) {
572 b2.addFloat64(p2[i]);
573 }
574 delete[] p1;
575 delete[] p2;
576 } break;
577
578 case VOCAB_REFERENCE: {
579 *ok = rpc_ITorque->getRefTorque(cmd.get(3).asInt32(), &dtmp);
580 response.addFloat64(dtmp);
581 } break;
582
583 case VOCAB_REFERENCES: {
584 auto* p = new double[controlledJoints];
585 *ok = rpc_ITorque->getRefTorques(p);
586 Bottle& b = response.addList();
587 for (size_t i = 0; i < controlledJoints; i++) {
588 b.addFloat64(p[i]);
589 }
590 delete[] p;
591 } break;
592 }
593 }
595 appendTimeStamp(response, lastRpcStamp);
596 break; // case VOCAB_GET
597 }
598}
599
601 yarp::os::Bottle& response,
602 bool* rec,
603 bool* ok)
604{
605 yCTrace(CONTROLBOARD, "\nHandling IInteractionMode message");
606 if (!rpc_IInteract) {
607 yCError(CONTROLBOARD, "Error I do not have a valid IInteractionMode interface");
608 *ok = false;
609 return;
610 }
611
612 yCTrace(CONTROLBOARD) << "received command: " << cmd.toString();
613
614 int action = cmd.get(0).asVocab32();
615
616 switch (action) {
617 case VOCAB_SET: {
618 switch (cmd.get(2).asVocab32()) {
622
625 } break;
626
628 yCTrace(CONTROLBOARD) << "CBW.h set interactionMode GROUP";
629
630 auto n_joints = static_cast<size_t>(cmd.get(3).asInt32());
631 jointList = cmd.get(4).asList();
632 modeList = cmd.get(5).asList();
633 if ((jointList->size() != n_joints) || (modeList->size() != n_joints)) {
634 yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vectors doesn´t match");
635 *ok = false;
636 break;
637 }
638 int* joints = new int[n_joints];
640 for (size_t i = 0; i < n_joints; i++) {
641 joints[i] = jointList->get(i).asInt32();
642 modes[i] = static_cast<yarp::dev::InteractionModeEnum>(modeList->get(i).asVocab32());
643 yCTrace(CONTROLBOARD) << "CBW.cpp received vocab " << yarp::os::Vocab32::decode(modes[i]);
644 }
646 delete[] joints;
647 delete[] modes;
648
649 } break;
650
652 yCTrace(CONTROLBOARD) << "CBW.c set interactionMode ALL";
653
654 modeList = cmd.get(3).asList();
655 if (modeList->size() != controlledJoints) {
656 yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vector doesn´t match the number of controlled joints");
657 *ok = false;
658 break;
659 }
661 for (size_t i = 0; i < controlledJoints; i++) {
662 modes[i] = static_cast<yarp::dev::InteractionModeEnum>(modeList->get(i).asVocab32());
663 }
665 delete[] modes;
666 } break;
667
668 default:
669 {
670 yCWarning(CONTROLBOARD, "Error while Handling IInteractionMode message, SET command not understood %s", cmd.get(2).asString().c_str());
671 *ok = false;
672 } break;
673 }
674 *rec = true; //or false
675 } break;
676
677 case VOCAB_GET: {
679
680 switch (cmd.get(2).asVocab32()) {
684 response.addVocab32(mode);
685 yCTrace(CONTROLBOARD) << " resp is " << response.toString();
686 } break;
687
690
691 int n_joints = cmd.get(3).asInt32();
692 jointList = cmd.get(4).asList();
693 if (jointList->size() != static_cast<size_t>(n_joints)) {
694 yCError(CONTROLBOARD, "Received an invalid getInteractionMode message. Size of vectors doesn´t match");
695 *ok = false;
696 break;
697 }
698 int* joints = new int[n_joints];
700 for (int i = 0; i < n_joints; i++) {
701 joints[i] = jointList->get(i).asInt32();
702 }
704
705 Bottle& c = response.addList();
706 for (int i = 0; i < n_joints; i++) {
707 c.addVocab32(modes[i]);
708 }
709
710 yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str());
711
712 delete[] joints;
713 delete[] modes;
714 } break;
715
719
721
722 Bottle& b = response.addList();
723 for (size_t i = 0; i < controlledJoints; i++) {
724 b.addVocab32(modes[i]);
725 }
726
727 yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str());
728
729 delete[] modes;
730 } break;
731 }
733 appendTimeStamp(response, lastRpcStamp);
734 } break; // case VOCAB_GET
735
736 default:
737 yCError(CONTROLBOARD, "Error while Handling IInteractionMode message, command was not SET nor GET");
738 *ok = false;
739 break;
740 }
741}
742
744{
745 yCTrace(CONTROLBOARD, "Handling ICurrentControl message");
746
747 if (!rpc_ICurrent) {
748 yCError(CONTROLBOARD, "I do not have a valid ICurrentControl interface");
749 *ok = false;
750 return;
751 }
752
753 int code = cmd.get(0).asVocab32();
754 int action = cmd.get(2).asVocab32();
755
756 *ok = false;
757 *rec = true;
758 switch (code) {
759 case VOCAB_SET: {
760 switch (action) {
761 case VOCAB_CURRENT_REF: {
762 yCError(CONTROLBOARD, "VOCAB_CURRENT_REF methods is implemented as streaming");
763 *ok = false;
764 } break;
765
766 case VOCAB_CURRENT_REFS: {
767 yCError(CONTROLBOARD, "VOCAB_CURRENT_REFS methods is implemented as streaming");
768 *ok = false;
769 } break;
770
772 yCError(CONTROLBOARD, "VOCAB_CURRENT_REF_GROUP methods is implemented as streaming");
773 *ok = false;
774 } break;
775
776 default:
777 {
778 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
779 *rec = false;
780 *ok = false;
781 } break;
782 }
783 } break;
784
785 case VOCAB_GET: {
786 *rec = true;
787 yCTrace(CONTROLBOARD, "get command received");
788 double dtmp = 0.0;
789 double dtmp2 = 0.0;
790 response.addVocab32(VOCAB_IS);
791 response.add(cmd.get(1));
792
793 switch (action) {
794 case VOCAB_CURRENT_REF: {
795 *ok = rpc_ICurrent->getRefCurrent(cmd.get(3).asInt32(), &dtmp);
796 response.addFloat64(dtmp);
797 } break;
798
799 case VOCAB_CURRENT_REFS: {
800 auto* p = new double[controlledJoints];
802 Bottle& b = response.addList();
803 for (size_t i = 0; i < controlledJoints; i++) {
804 b.addFloat64(p[i]);
805 }
806 delete[] p;
807 } break;
808
809 case VOCAB_CURRENT_RANGE: {
810
811 *ok = rpc_ICurrent->getCurrentRange(cmd.get(3).asInt32(), &dtmp, &dtmp2);
812 response.addFloat64(dtmp);
813 response.addFloat64(dtmp2);
814 } break;
815
817 auto* p1 = new double[controlledJoints];
818 auto* p2 = new double[controlledJoints];
820 Bottle& b1 = response.addList();
821 Bottle& b2 = response.addList();
822 for (size_t i = 0; i < controlledJoints; i++) {
823 b1.addFloat64(p1[i]);
824 }
825 for (size_t i = 0; i < controlledJoints; i++) {
826 b2.addFloat64(p2[i]);
827 }
828 delete[] p1;
829 delete[] p2;
830 } break;
831
832 default:
833 {
834 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
835 *rec = false;
836 *ok = false;
837 } break;
838 }
839 } break;
840
841 default:
842 {
843 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
844 *rec = false;
845 *ok = false;
846 } break;
847 }
848}
849
850void RPCMessagesParser::handlePidMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok)
851{
852 yCTrace(CONTROLBOARD, "Handling IPidControl message");
853
854 if (!rpc_IPid) {
855 yCError(CONTROLBOARD, "I do not have a valid IPidControl interface");
856 *ok = false;
857 return;
858 }
859
860 int code = cmd.get(0).asVocab32();
861 int action = cmd.get(2).asVocab32();
862 auto pidtype = static_cast<yarp::dev::PidControlTypeEnum>(cmd.get(3).asVocab32());
863
864 *ok = false;
865 *rec = true;
866 switch (code) {
867 case VOCAB_SET: {
868 *rec = true;
869 yCTrace(CONTROLBOARD, "set command received");
870
871 switch (action) {
872 case VOCAB_OFFSET: {
873 double v;
874 int j = cmd.get(4).asInt32();
875 v = cmd.get(5).asFloat64();
876 *ok = rpc_IPid->setPidOffset(pidtype, j, v);
877 } break;
878
879 case VOCAB_PID: {
880 Pid p;
881 int j = cmd.get(4).asInt32();
882 Bottle* b = cmd.get(5).asList();
883
884 if (b == nullptr) {
885 break;
886 }
887
888 p.kp = b->get(0).asFloat64();
889 p.kd = b->get(1).asFloat64();
890 p.ki = b->get(2).asFloat64();
891 p.max_int = b->get(3).asFloat64();
892 p.max_output = b->get(4).asFloat64();
893 p.offset = b->get(5).asFloat64();
894 p.scale = b->get(6).asFloat64();
895 p.stiction_up_val = b->get(7).asFloat64();
896 p.stiction_down_val = b->get(8).asFloat64();
897 p.kff = b->get(9).asFloat64();
898 *ok = rpc_IPid->setPid(pidtype, j, p);
899 } break;
900
901 case VOCAB_PIDS: {
902 Bottle* b = cmd.get(4).asList();
903
904 if (b == nullptr) {
905 break;
906 }
907
908 const size_t njs = b->size();
909 if (njs == controlledJoints) {
910 Pid* p = new Pid[njs];
911
912 bool allOK = true;
913
914 for (size_t i = 0; i < njs; i++) {
915 Bottle* c = b->get(i).asList();
916 if (c != nullptr) {
917 p[i].kp = c->get(0).asFloat64();
918 p[i].kd = c->get(1).asFloat64();
919 p[i].ki = c->get(2).asFloat64();
920 p[i].max_int = c->get(3).asFloat64();
921 p[i].max_output = c->get(4).asFloat64();
922 p[i].offset = c->get(5).asFloat64();
923 p[i].scale = c->get(6).asFloat64();
924 p[i].stiction_up_val = c->get(7).asFloat64();
925 p[i].stiction_down_val = c->get(8).asFloat64();
926 p[i].kff = c->get(9).asFloat64();
927 } else {
928 allOK = false;
929 }
930 }
931 if (allOK) {
932 *ok = rpc_IPid->setPids(pidtype, p);
933 } else {
934 *ok = false;
935 }
936
937 delete[] p;
938 }
939 } break;
940
941 case VOCAB_REF: {
942 *ok = rpc_IPid->setPidReference(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64());
943 } break;
944
945 case VOCAB_REFS: {
946 Bottle* b = cmd.get(4).asList();
947
948 if (b == nullptr) {
949 break;
950 }
951
952 const size_t njs = b->size();
953 if (njs == controlledJoints) {
954 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
955 for (size_t i = 0; i < njs; i++) {
956 p[i] = b->get(i).asFloat64();
957 }
959 delete[] p;
960 }
961 } break;
962
963 case VOCAB_LIM: {
964 *ok = rpc_IPid->setPidErrorLimit(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64());
965 } break;
966
967 case VOCAB_LIMS: {
968 Bottle* b = cmd.get(4).asList();
969
970 if (b == nullptr) {
971 break;
972 }
973
974 const size_t njs = b->size();
975 if (njs == controlledJoints) {
976 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
977 for (size_t i = 0; i < njs; i++) {
978 p[i] = b->get(i).asFloat64();
979 }
981 delete[] p;
982 }
983 } break;
984
985 case VOCAB_RESET: {
986 *ok = rpc_IPid->resetPid(pidtype, cmd.get(4).asInt32());
987 } break;
988
989 case VOCAB_DISABLE: {
990 *ok = rpc_IPid->disablePid(pidtype, cmd.get(4).asInt32());
991 } break;
992
993 case VOCAB_ENABLE: {
994 *ok = rpc_IPid->enablePid(pidtype, cmd.get(4).asInt32());
995 } break;
996 }
997 } break;
998
999 case VOCAB_GET: {
1000 *rec = true;
1001 yCTrace(CONTROLBOARD, "get command received");
1002 double dtmp = 0.0;
1003 response.addVocab32(VOCAB_IS);
1004 response.add(cmd.get(1));
1005
1006 switch (action) {
1007 case VOCAB_LIMS: {
1008 auto* p = new double[controlledJoints];
1010 Bottle& b = response.addList();
1011 for (size_t i = 0; i < controlledJoints; i++) {
1012 b.addFloat64(p[i]);
1013 }
1014 delete[] p;
1015 } break;
1016
1017 case VOCAB_ENABLE: {
1018 bool booltmp = false;
1019 *ok = rpc_IPid->isPidEnabled(pidtype, cmd.get(4).asInt32(), &booltmp);
1020 response.addInt32(booltmp);
1021 } break;
1022
1023 case VOCAB_ERR: {
1024 *ok = rpc_IPid->getPidError(pidtype, cmd.get(4).asInt32(), &dtmp);
1025 response.addFloat64(dtmp);
1026 } break;
1027
1028 case VOCAB_ERRS: {
1029 auto* p = new double[controlledJoints];
1030 *ok = rpc_IPid->getPidErrors(pidtype, p);
1031 Bottle& b = response.addList();
1032 for (size_t i = 0; i < controlledJoints; i++) {
1033 b.addFloat64(p[i]);
1034 }
1035 delete[] p;
1036 } break;
1037
1038 case VOCAB_OUTPUT: {
1039 *ok = rpc_IPid->getPidOutput(pidtype, cmd.get(4).asInt32(), &dtmp);
1040 response.addFloat64(dtmp);
1041 } break;
1042
1043 case VOCAB_OUTPUTS: {
1044 auto* p = new double[controlledJoints];
1045 *ok = rpc_IPid->getPidOutputs(pidtype, p);
1046 Bottle& b = response.addList();
1047 for (size_t i = 0; i < controlledJoints; i++) {
1048 b.addFloat64(p[i]);
1049 }
1050 delete[] p;
1051 } break;
1052
1053 case VOCAB_PID: {
1054 Pid p;
1055 *ok = rpc_IPid->getPid(pidtype, cmd.get(4).asInt32(), &p);
1056 Bottle& b = response.addList();
1057 b.addFloat64(p.kp);
1058 b.addFloat64(p.kd);
1059 b.addFloat64(p.ki);
1060 b.addFloat64(p.max_int);
1062 b.addFloat64(p.offset);
1063 b.addFloat64(p.scale);
1066 b.addFloat64(p.kff);
1067 } break;
1068
1069 case VOCAB_PIDS: {
1070 Pid* p = new Pid[controlledJoints];
1071 *ok = rpc_IPid->getPids(pidtype, p);
1072 Bottle& b = response.addList();
1073 for (size_t i = 0; i < controlledJoints; i++) {
1074 Bottle& c = b.addList();
1075 c.addFloat64(p[i].kp);
1076 c.addFloat64(p[i].kd);
1077 c.addFloat64(p[i].ki);
1078 c.addFloat64(p[i].max_int);
1079 c.addFloat64(p[i].max_output);
1080 c.addFloat64(p[i].offset);
1081 c.addFloat64(p[i].scale);
1082 c.addFloat64(p[i].stiction_up_val);
1083 c.addFloat64(p[i].stiction_down_val);
1084 c.addFloat64(p[i].kff);
1085 }
1086 delete[] p;
1087 } break;
1088
1089 case VOCAB_REFERENCE: {
1090 *ok = rpc_IPid->getPidReference(pidtype, cmd.get(4).asInt32(), &dtmp);
1091 response.addFloat64(dtmp);
1092 } break;
1093
1094 case VOCAB_REFERENCES: {
1095 auto* p = new double[controlledJoints];
1097 Bottle& b = response.addList();
1098 for (size_t i = 0; i < controlledJoints; i++) {
1099 b.addFloat64(p[i]);
1100 }
1101 delete[] p;
1102 } break;
1103
1104 case VOCAB_LIM: {
1105 *ok = rpc_IPid->getPidErrorLimit(pidtype, cmd.get(4).asInt32(), &dtmp);
1106 response.addFloat64(dtmp);
1107 } break;
1108 }
1109 } break;
1110
1111 default:
1112 {
1113 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1114 *rec = false;
1115 *ok = false;
1116 } break;
1117 }
1118}
1119
1120void RPCMessagesParser::handlePWMMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok)
1121{
1122 yCTrace(CONTROLBOARD, "Handling IPWMControl message");
1123
1124 if (!rpc_IPWM) {
1125 yCError(CONTROLBOARD, "I do not have a valid IPWMControl interface");
1126 *ok = false;
1127 return;
1128 }
1129
1130 int code = cmd.get(0).asVocab32();
1131 int action = cmd.get(2).asVocab32();
1132
1133 *ok = false;
1134 *rec = true;
1135 switch (code) {
1136 case VOCAB_SET: {
1137 *rec = true;
1138 yCTrace(CONTROLBOARD, "set command received");
1139
1140 switch (action) {
1142 //handled as streaming!
1143 yCError(CONTROLBOARD) << "VOCAB_PWMCONTROL_REF_PWM handled as straming";
1144 *ok = false;
1145 } break;
1146
1147 default:
1148 {
1149 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1150 *ok = false;
1151 } break;
1152 }
1153 } break;
1154
1155 case VOCAB_GET: {
1156 yCTrace(CONTROLBOARD, "get command received");
1157 *rec = true;
1158 double dtmp = 0.0;
1159 response.addVocab32(VOCAB_IS);
1160 response.add(cmd.get(1));
1161
1162 switch (action) {
1164 *ok = rpc_IPWM->getRefDutyCycle(cmd.get(3).asInt32(), &dtmp);
1165 response.addFloat64(dtmp);
1166 } break;
1167
1169 auto* p = new double[controlledJoints];
1170 *ok = rpc_IPWM->getRefDutyCycles(p);
1171 Bottle& b = response.addList();
1172 for (size_t i = 0; i < controlledJoints; i++) {
1173 b.addFloat64(p[i]);
1174 }
1175 delete[] p;
1176 } break;
1177
1179 *ok = rpc_IPWM->getDutyCycle(cmd.get(3).asInt32(), &dtmp);
1180 response.addFloat64(dtmp);
1181 } break;
1182
1184 auto* p = new double[controlledJoints];
1185 *ok = rpc_IPWM->getRefDutyCycles(p);
1186 Bottle& b = response.addList();
1187 for (size_t i = 0; i < controlledJoints; i++) {
1188 b.addFloat64(p[i]);
1189 }
1190 delete[] p;
1191 } break;
1192
1193 default:
1194 {
1195 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1196 *ok = false;
1197 } break;
1198 }
1199 } break;
1200
1201 default:
1202 {
1203 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1204 *rec = false;
1205 *ok = false;
1206 } break;
1207 }
1208}
1209
1211{
1212 yCTrace(CONTROLBOARD, "Handling IRemoteVariables message");
1213
1214 if (!rpc_IVar) {
1215 yCError(CONTROLBOARD, "I do not have a valid IRemoteVariables interface");
1216 *ok = false;
1217 return;
1218 }
1219
1220 int code = cmd.get(0).asVocab32();
1221 int action = cmd.get(2).asVocab32();
1222
1223 *ok = false;
1224 *rec = true;
1225 switch (code) {
1226 case VOCAB_SET: {
1227 switch (action) {
1228 case VOCAB_VARIABLE: {
1229 Bottle btail = cmd.tail().tail().tail().tail(); // remove the first four elements
1230 std::string s = btail.toString();
1231 *ok = rpc_IVar->setRemoteVariable(cmd.get(3).asString(), btail);
1232 } break;
1233
1234 default:
1235 {
1236 *rec = false;
1237 *ok = false;
1238 } break;
1239 }
1240 } break;
1241
1242 case VOCAB_GET: {
1243 yCTrace(CONTROLBOARD, "get command received");
1244
1245 response.clear();
1246 response.addVocab32(VOCAB_IS);
1247 response.add(cmd.get(1));
1248 Bottle btmp;
1249
1250 switch (action) {
1251 case VOCAB_VARIABLE: {
1252 *ok = rpc_IVar->getRemoteVariable(cmd.get(3).asString(), btmp);
1253 Bottle& b = response.addList();
1254 b = btmp;
1255 } break;
1256
1257 case VOCAB_LIST_VARIABLES: {
1259 Bottle& b = response.addList();
1260 b = btmp;
1261 } break;
1262 }
1263 }
1264 } //end get/set switch
1265}
1266
1268{
1269 yCTrace(CONTROLBOARD, "Handling IRemoteCalibrator message");
1270
1271 if (!rpc_IRemoteCalibrator) {
1272 yCError(CONTROLBOARD, "I do not have a valid IRemoteCalibrator interface");
1273 *ok = false;
1274 return;
1275 }
1276
1277 int code = cmd.get(0).asVocab32();
1278 int action = cmd.get(2).asVocab32();
1279
1280 *ok = false;
1281 *rec = true;
1282 switch (code) {
1283 case VOCAB_SET: {
1284 switch (action) {
1286 yCDebug(CONTROLBOARD) << "cmd is " << cmd.toString() << " joint is " << cmd.get(3).asInt32();
1287 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1289 } break;
1290
1292 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1294 } break;
1295
1297 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1299 } break;
1300
1302 yCDebug(CONTROLBOARD) << "Received homing whole part";
1303 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1305 } break;
1306
1308 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1310 } break;
1311
1312 case VOCAB_PARK_WHOLE_PART: {
1313 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1315 } break;
1316
1317 case VOCAB_QUIT_CALIBRATE: {
1318 yCTrace(CONTROLBOARD, "Calling quit calibrate");
1320 } break;
1321
1322 case VOCAB_QUIT_PARK: {
1323 yCTrace(CONTROLBOARD, "Calling quit park");
1325 } break;
1326
1327 default:
1328 {
1329 *rec = false;
1330 *ok = false;
1331 } break;
1332 }
1333 } break;
1334
1335 case VOCAB_GET: {
1336 response.clear();
1337 response.addVocab32(VOCAB_IS);
1338 response.add(cmd.get(1));
1339
1340 switch (action) {
1342 bool tmp;
1343 yCTrace(CONTROLBOARD, "Calling VOCAB_IS_CALIBRATOR_PRESENT");
1345 response.addInt32(tmp);
1346 } break;
1347 }
1348 }
1349 } //end get/set switch
1350}
1351
1352
1353// rpc callback
1355{
1356 bool ok = false;
1357 bool rec = false; // Tells if the command is recognized!
1358
1359 yCTrace(CONTROLBOARD, "command received: %s", cmd.toString().c_str());
1360
1361 int code = cmd.get(0).asVocab32();
1362
1363 if (cmd.size() < 2) {
1364 ok = false;
1365 } else {
1366 switch (cmd.get(1).asVocab32()) {
1367 case VOCAB_PID:
1368 handlePidMsg(cmd, response, &rec, &ok);
1369 break;
1370
1371 case VOCAB_TORQUE:
1372 handleTorqueMsg(cmd, response, &rec, &ok);
1373 break;
1374
1375 case VOCAB_IJOINTFAULT:
1376 handleJointFaultMsg(cmd, response, &rec, &ok);
1377 break;
1378
1379 case VOCAB_ICONTROLMODE:
1380 handleControlModeMsg(cmd, response, &rec, &ok);
1381 break;
1382
1383 case VOCAB_IMPEDANCE:
1384 handleImpedanceMsg(cmd, response, &rec, &ok);
1385 break;
1386
1388 handleInteractionModeMsg(cmd, response, &rec, &ok);
1389 break;
1390
1392 handleRemoteCalibratorMsg(cmd, response, &rec, &ok);
1393 break;
1394
1396 handleRemoteVariablesMsg(cmd, response, &rec, &ok);
1397 break;
1398
1400 handleCurrentMsg(cmd, response, &rec, &ok);
1401 break;
1402
1404 handlePWMMsg(cmd, response, &rec, &ok);
1405 break;
1406
1407 default:
1408 // fallback for old interfaces with no specific name
1409 switch (code) {
1410 case VOCAB_CALIBRATE_JOINT: {
1411 if (!rpc_Icalib) { ok = false; break; }
1412 rec = true;
1413 yCTrace(CONTROLBOARD, "Calling calibrate joint");
1414
1415 int j = cmd.get(1).asInt32();
1416 int ui = cmd.get(2).asInt32();
1417 double v1 = cmd.get(3).asFloat64();
1418 double v2 = cmd.get(4).asFloat64();
1419 double v3 = cmd.get(5).asFloat64();
1420 if (rpc_Icalib == nullptr) {
1421 yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface");
1422 } else {
1423 ok = rpc_Icalib->calibrateAxisWithParams(j, ui, v1, v2, v3);
1424 }
1425 } break;
1426
1428 if (!rpc_Icalib) { ok = false; break; }
1429 rec = true;
1430 yCTrace(CONTROLBOARD, "Calling calibrate joint");
1431
1432 int j = cmd.get(1).asInt32();
1433 CalibrationParameters params;
1434 params.type = cmd.get(2).asInt32();
1435 params.param1 = cmd.get(3).asFloat64();
1436 params.param2 = cmd.get(4).asFloat64();
1437 params.param3 = cmd.get(5).asFloat64();
1438 params.param4 = cmd.get(6).asFloat64();
1439 if (rpc_Icalib == nullptr) {
1440 yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface");
1441 } else {
1442 ok = rpc_Icalib->setCalibrationParameters(j, params);
1443 }
1444 } break;
1445
1446 case VOCAB_CALIBRATE: {
1447 if (!rpc_Icalib) { ok = false; break; }
1448 rec = true;
1449 yCTrace(CONTROLBOARD, "Calling calibrate");
1450 ok = rpc_Icalib->calibrateRobot();
1451 } break;
1452
1453 case VOCAB_CALIBRATE_DONE: {
1454 if (!rpc_Icalib) { ok = false; break; }
1455 rec = true;
1456 yCTrace(CONTROLBOARD, "Calling calibrate done");
1457 int j = cmd.get(1).asInt32();
1458 ok = rpc_Icalib->calibrationDone(j);
1459 } break;
1460
1461 case VOCAB_PARK: {
1462 if (!rpc_Icalib) { ok = false; break; }
1463 rec = true;
1464 yCTrace(CONTROLBOARD, "Calling park function");
1465 int flag = cmd.get(1).asInt32();
1466 ok = rpc_Icalib->park(flag ? true : false);
1467 ok = true; //client would get stuck if returning false
1468 } break;
1469
1470 case VOCAB_SET: {
1471 rec = true;
1472 yCTrace(CONTROLBOARD, "set command received");
1473
1474 switch (cmd.get(1).asVocab32()) {
1475 case VOCAB_POSITION_MOVE: {
1476 if (!rpc_IPosCtrl) { ok = false; break; }
1477 ok = rpc_IPosCtrl->positionMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1478 } break;
1479
1480 // this operation is also available on "command" port
1481 case VOCAB_POSITION_MOVES: {
1482 if (!rpc_IPosCtrl) { ok = false; break; }
1483 Bottle* b = cmd.get(2).asList();
1484 if (b == nullptr) {
1485 break;
1486 }
1487 const size_t njs = b->size();
1488 if (njs != controlledJoints) {
1489 break;
1490 }
1492 for (size_t i = 0; i < njs; i++) {
1493 tmpVect[i] = b->get(i).asFloat64();
1494 }
1495
1496 if (rpc_IPosCtrl != nullptr) {
1498 }
1499 } break;
1500
1502 if (!rpc_IPosCtrl) { ok = false; break; }
1503 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1504 Bottle* jlut = cmd.get(3).asList();
1505 Bottle* pos_val = cmd.get(4).asList();
1506
1507 if (rpc_IPosCtrl == nullptr) {
1508 break;
1509 }
1510
1511 if (jlut == nullptr || pos_val == nullptr) {
1512 break;
1513 }
1514 if (len != jlut->size() || len != pos_val->size()) {
1515 break;
1516 }
1517
1518 auto* j_tmp = new int[len];
1519 auto* pos_tmp = new double[len];
1520 for (size_t i = 0; i < len; i++) {
1521 j_tmp[i] = jlut->get(i).asInt32();
1522 pos_tmp[i] = pos_val->get(i).asFloat64();
1523 }
1524
1526
1527 delete[] j_tmp;
1528 delete[] pos_tmp;
1529 } break;
1530
1531 // this operation is also available on "command" port
1532 case VOCAB_VELOCITY_MOVES: {
1533 if (!rpc_IVelCtrl) { ok = false; break; }
1534 Bottle* b = cmd.get(2).asList();
1535 if (b == nullptr) {
1536 break;
1537 }
1538 const size_t njs = b->size();
1539 if (njs != controlledJoints) {
1540 break;
1541 }
1543 for (size_t i = 0; i < njs; i++) {
1544 tmpVect[i] = b->get(i).asFloat64();
1545 }
1546 if (rpc_IVelCtrl != nullptr) {
1548 }
1549
1550 } break;
1551
1552 case VOCAB_RELATIVE_MOVE: {
1553 if (!rpc_IPosCtrl) { ok = false; break; }
1554 ok = rpc_IPosCtrl->relativeMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1555 } break;
1556
1558 if (!rpc_IPosCtrl) { ok = false; break; }
1559 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1560 Bottle* jBottle_p = cmd.get(3).asList();
1561 Bottle* posBottle_p = cmd.get(4).asList();
1562
1563 if (rpc_IPosCtrl == nullptr) {
1564 break;
1565 }
1566
1567 if (jBottle_p == nullptr || posBottle_p == nullptr) {
1568 break;
1569 }
1570 if (len != jBottle_p->size() || len != posBottle_p->size()) {
1571 break;
1572 }
1573
1574 int* j_tmp = new int[len];
1575 auto* pos_tmp = new double[len];
1576
1577 for (size_t i = 0; i < len; i++) {
1578 j_tmp[i] = jBottle_p->get(i).asInt32();
1579 }
1580
1581 for (size_t i = 0; i < len; i++) {
1582 pos_tmp[i] = posBottle_p->get(i).asFloat64();
1583 }
1584
1586
1587 delete[] j_tmp;
1588 delete[] pos_tmp;
1589 } break;
1590
1591 case VOCAB_RELATIVE_MOVES: {
1592 if (!rpc_IPosCtrl) { ok = false; break; }
1593 Bottle* b = cmd.get(2).asList();
1594
1595 if (b == nullptr) {
1596 break;
1597 }
1598
1599 const size_t njs = b->size();
1600 if (njs != controlledJoints) {
1601 break;
1602 }
1603 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1604 for (size_t i = 0; i < njs; i++) {
1605 p[i] = b->get(i).asFloat64();
1606 }
1607 ok = rpc_IPosCtrl->relativeMove(p);
1608 delete[] p;
1609 } break;
1610
1611 case VOCAB_REF_SPEED: {
1612 if (!rpc_IPosCtrl) { ok = false; break; }
1613 ok = rpc_IPosCtrl->setRefSpeed(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1614 } break;
1615
1616 case VOCAB_REF_SPEED_GROUP: {
1617 if (!rpc_IPosCtrl) { ok = false; break; }
1618 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1619 Bottle* jBottle_p = cmd.get(3).asList();
1620 Bottle* velBottle_p = cmd.get(4).asList();
1621
1622 if (rpc_IPosCtrl == nullptr) {
1623 break;
1624 }
1625
1626 if (jBottle_p == nullptr || velBottle_p == nullptr) {
1627 break;
1628 }
1629 if (len != jBottle_p->size() || len != velBottle_p->size()) {
1630 break;
1631 }
1632
1633 int* j_tmp = new int[len];
1634 auto* spds_tmp = new double[len];
1635
1636 for (size_t i = 0; i < len; i++) {
1637 j_tmp[i] = jBottle_p->get(i).asInt32();
1638 }
1639
1640 for (size_t i = 0; i < len; i++) {
1641 spds_tmp[i] = velBottle_p->get(i).asFloat64();
1642 }
1643
1645 delete[] j_tmp;
1646 delete[] spds_tmp;
1647 } break;
1648
1649 case VOCAB_REF_SPEEDS: {
1650 if (!rpc_IPosCtrl) { ok = false; break; }
1651 Bottle* b = cmd.get(2).asList();
1652
1653 if (b == nullptr) {
1654 break;
1655 }
1656
1657 const size_t njs = b->size();
1658 if (njs != controlledJoints) {
1659 break;
1660 }
1661 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1662 for (size_t i = 0; i < njs; i++) {
1663 p[i] = b->get(i).asFloat64();
1664 }
1665 ok = rpc_IPosCtrl->setRefSpeeds(p);
1666 delete[] p;
1667 } break;
1668
1670 if (!rpc_IPosCtrl) { ok = false; break; }
1671 ok = rpc_IPosCtrl->setRefAcceleration(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1672 } break;
1673
1675 if (!rpc_IPosCtrl) { ok = false; break; }
1676 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1677 Bottle* jBottle_p = cmd.get(3).asList();
1678 Bottle* accBottle_p = cmd.get(4).asList();
1679
1680 if (rpc_IPosCtrl == nullptr) {
1681 break;
1682 }
1683
1684 if (jBottle_p == nullptr || accBottle_p == nullptr) {
1685 break;
1686 }
1687 if (len != jBottle_p->size() || len != accBottle_p->size()) {
1688 break;
1689 }
1690
1691 int* j_tmp = new int[len];
1692 auto* accs_tmp = new double[len];
1693
1694 for (size_t i = 0; i < len; i++) {
1695 j_tmp[i] = jBottle_p->get(i).asInt32();
1696 }
1697
1698 for (size_t i = 0; i < len; i++) {
1699 accs_tmp[i] = accBottle_p->get(i).asFloat64();
1700 }
1701
1703 delete[] j_tmp;
1704 delete[] accs_tmp;
1705 } break;
1706
1708 if (!rpc_IPosCtrl) { ok = false; break; }
1709 Bottle* b = cmd.get(2).asList();
1710
1711 if (b == nullptr) {
1712 break;
1713 }
1714
1715 const size_t njs = b->size();
1716 if (njs != controlledJoints) {
1717 break;
1718 }
1719 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1720 for (size_t i = 0; i < njs; i++) {
1721 p[i] = b->get(i).asFloat64();
1722 }
1724 delete[] p;
1725 } break;
1726
1727 case VOCAB_STOP: {
1728 if (!rpc_IPosCtrl) { ok = false; break; }
1729 ok = rpc_IPosCtrl->stop(cmd.get(2).asInt32());
1730 } break;
1731
1732 case VOCAB_STOP_GROUP: {
1733 if (!rpc_IPosCtrl) { ok = false; break; }
1734 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1735 Bottle* jBottle_p = cmd.get(3).asList();
1736
1737 if (rpc_IPosCtrl == nullptr) {
1738 break;
1739 }
1740
1741 if (jBottle_p == nullptr) {
1742 break;
1743 }
1744 if (len != jBottle_p->size()) {
1745 break;
1746 }
1747
1748 int* j_tmp = new int[len];
1749
1750 for (size_t i = 0; i < len; i++) {
1751 j_tmp[i] = jBottle_p->get(i).asInt32();
1752 }
1753
1754 ok = rpc_IPosCtrl->stop(len, j_tmp);
1755 delete[] j_tmp;
1756 } break;
1757
1758 case VOCAB_STOPS: {
1759 if (!rpc_IPosCtrl) { ok = false; break; }
1760 ok = rpc_IPosCtrl->stop();
1761 } break;
1762
1763 case VOCAB_E_RESET: {
1764 if (!rpc_IEncTimed) { ok = false; break; }
1765 ok = rpc_IEncTimed->resetEncoder(cmd.get(2).asInt32());
1766 } break;
1767
1768 case VOCAB_E_RESETS: {
1769 if (!rpc_IEncTimed) { ok = false; break; }
1771 } break;
1772
1773 case VOCAB_ENCODER: {
1774 if (!rpc_IEncTimed) { ok = false; break; }
1775 ok = rpc_IEncTimed->setEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1776 } break;
1777
1778 case VOCAB_ENCODERS: {
1779 if (!rpc_IEncTimed) { ok = false; break; }
1780 Bottle* b = cmd.get(2).asList();
1781
1782 if (b == nullptr) {
1783 break;
1784 }
1785
1786 const size_t njs = b->size();
1787 if (njs != controlledJoints) {
1788 break;
1789 }
1790 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1791 for (size_t i = 0; i < njs; i++) {
1792 p[i] = b->get(i).asFloat64();
1793 }
1794 ok = rpc_IEncTimed->setEncoders(p);
1795 delete[] p;
1796 } break;
1797
1798 case VOCAB_MOTOR_CPR: {
1799 if (!rpc_IMotEnc) { ok = false; break; }
1801 } break;
1802
1803 case VOCAB_MOTOR_E_RESET: {
1804 if (!rpc_IMotEnc) { ok = false; break; }
1805 ok = rpc_IMotEnc->resetMotorEncoder(cmd.get(2).asInt32());
1806 } break;
1807
1808 case VOCAB_MOTOR_E_RESETS: {
1809 if (!rpc_IMotEnc) { ok = false; break; }
1811 } break;
1812
1813 case VOCAB_MOTOR_ENCODER: {
1814 if (!rpc_IMotEnc) { ok = false; break; }
1815 ok = rpc_IMotEnc->setMotorEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1816 } break;
1817
1818 case VOCAB_MOTOR_ENCODERS: {
1819 if (!rpc_IMotEnc) { ok = false; break; }
1820 Bottle* b = cmd.get(2).asList();
1821
1822 if (b == nullptr) {
1823 break;
1824 }
1825
1826 const size_t njs = b->size();
1827 if (njs != controlledJoints) {
1828 break;
1829 }
1830 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1831 for (size_t i = 0; i < njs; i++) {
1832 p[i] = b->get(i).asFloat64();
1833 }
1835 delete[] p;
1836 } break;
1837
1838 case VOCAB_AMP_ENABLE: {
1839 if (!rcp_IAmp) { ok = false; break; }
1840 ok = rcp_IAmp->enableAmp(cmd.get(2).asInt32());
1841 } break;
1842
1843 case VOCAB_AMP_DISABLE: {
1844 if (!rcp_IAmp) { ok = false; break; }
1845 ok = rcp_IAmp->disableAmp(cmd.get(2).asInt32());
1846 } break;
1847
1848 case VOCAB_AMP_MAXCURRENT: {
1849 if (!rcp_IAmp) { ok = false; break; }
1850 ok = rcp_IAmp->setMaxCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1851 } break;
1852
1854 if (!rcp_IAmp) { ok = false; break; }
1855 ok = rcp_IAmp->setPeakCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1856 } break;
1857
1859 if (!rcp_IAmp) { ok = false; break; }
1860 ok = rcp_IAmp->setNominalCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1861 } break;
1862
1863 case VOCAB_AMP_PWM_LIMIT: {
1864 if (!rcp_IAmp) { ok = false; break; }
1865 ok = rcp_IAmp->setPWMLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1866 } break;
1867
1868 case VOCAB_LIMITS: {
1869 if (!rcp_Ilim) {ok= false; break;}
1870 ok = rcp_Ilim->setLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64());
1871 } break;
1872
1873
1875 if (!rpc_IMotor) { ok = false; break; }
1876 ok = rpc_IMotor->setTemperatureLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1877 } break;
1878
1879 case VOCAB_GEARBOX_RATIO: {
1880 if (!rpc_IMotor) { ok = false; break; }
1881 ok = rpc_IMotor->setGearboxRatio(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1882 } break;
1883
1884 case VOCAB_VEL_LIMITS: {
1885 if (!rcp_Ilim) { ok = false; break; }
1886 ok = rcp_Ilim->setVelLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64());
1887 } break;
1888
1889 default:
1890 {
1891 yCError(CONTROLBOARD, "received an unknown command after a VOCAB_SET (%s)", cmd.toString().c_str());
1892 } break;
1893 } //switch(cmd.get(1).asVocab32()
1894 break;
1895 }
1896
1897 case VOCAB_GET: {
1898 rec = true;
1899 yCTrace(CONTROLBOARD, "get command received");
1900
1901 double dtmp = 0.0;
1902 Bottle btmp;
1903 response.addVocab32(VOCAB_IS);
1904 response.add(cmd.get(1));
1905
1906 switch (cmd.get(1).asVocab32()) {
1907
1909 if (!rpc_IMotor) { ok = false; break; }
1910 ok = rpc_IMotor->getTemperatureLimit(cmd.get(2).asInt32(), &dtmp);
1911 response.addFloat64(dtmp);
1912 } break;
1913
1914 case VOCAB_TEMPERATURE: {
1915 if (!rpc_IMotor) { ok = false; break; }
1916 ok = rpc_IMotor->getTemperature(cmd.get(2).asInt32(), &dtmp);
1917 response.addFloat64(dtmp);
1918 } break;
1919
1920 case VOCAB_GEARBOX_RATIO: {
1921 if (!rpc_IMotor) { ok = false; break; }
1922 ok = rpc_IMotor->getGearboxRatio(cmd.get(2).asInt32(), &dtmp);
1923 response.addFloat64(dtmp);
1924 } break;
1925
1926 case VOCAB_TEMPERATURES: {
1927 if (!rpc_IMotor) { ok = false; break; }
1928 auto* p = new double[controlledJoints];
1929 ok = rpc_IMotor->getTemperatures(p);
1930 Bottle& b = response.addList();
1931 for (size_t i = 0; i < controlledJoints; i++) {
1932 b.addFloat64(p[i]);
1933 }
1934 delete[] p;
1935 } break;
1936
1937 case VOCAB_AMP_MAXCURRENT: {
1938 if (!rcp_IAmp) { ok = false; break; }
1939 ok = rcp_IAmp->getMaxCurrent(cmd.get(2).asInt32(), &dtmp);
1940 response.addFloat64(dtmp);
1941 } break;
1942
1943 case VOCAB_POSITION_MOVE: {
1944 if (!rpc_IPosCtrl) { ok = false; break; }
1945 yCTrace(CONTROLBOARD, "getTargetPosition");
1946 ok = rpc_IPosCtrl->getTargetPosition(cmd.get(2).asInt32(), &dtmp);
1947
1948 response.addFloat64(dtmp);
1949 rec = true;
1950 } break;
1951
1953 if (!rpc_IPosCtrl) { ok = false; break; }
1954 int len = cmd.get(2).asInt32();
1955 Bottle& in = *(cmd.get(3).asList());
1956 int* jointList = new int[len];
1957 auto* refs = new double[len];
1958
1959 for (int j = 0; j < len; j++) {
1960 jointList[j] = in.get(j).asInt32();
1961 }
1963
1964 Bottle& b = response.addList();
1965 for (int i = 0; i < len; i++) {
1966 b.addFloat64(refs[i]);
1967 }
1968
1969 delete[] jointList;
1970 delete[] refs;
1971 } break;
1972
1973 case VOCAB_POSITION_MOVES: {
1974 if (!rpc_IPosCtrl) { ok = false; break; }
1975 auto* refs = new double[controlledJoints];
1977 Bottle& b = response.addList();
1978 for (size_t i = 0; i < controlledJoints; i++) {
1979 b.addFloat64(refs[i]);
1980 }
1981 delete[] refs;
1982 } break;
1983
1984 case VOCAB_POSITION_DIRECT: {
1985 if (!rpc_IPosDirect) { ok = false; break; }
1986 yCTrace(CONTROLBOARD, "getRefPosition");
1987 ok = rpc_IPosDirect->getRefPosition(cmd.get(2).asInt32(), &dtmp);
1988
1989 response.addFloat64(dtmp);
1990 rec = true;
1991 } break;
1992
1994 if (!rpc_IPosDirect) { ok = false; break; }
1995 int len = cmd.get(2).asInt32();
1996 Bottle& in = *(cmd.get(3).asList());
1997 int* jointList = new int[len];
1998 auto* refs = new double[len];
1999
2000 for (int j = 0; j < len; j++) {
2001 jointList[j] = in.get(j).asInt32();
2002 }
2004
2005 Bottle& b = response.addList();
2006 for (int i = 0; i < len; i++) {
2007 b.addFloat64(refs[i]);
2008 }
2009
2010 delete[] jointList;
2011 delete[] refs;
2012 } break;
2013
2015 auto* refs = new double[controlledJoints];
2017 Bottle& b = response.addList();
2018 for (size_t i = 0; i < controlledJoints; i++) {
2019 b.addFloat64(refs[i]);
2020 }
2021 delete[] refs;
2022 } break;
2023
2024 case VOCAB_VELOCITY_MOVE: {
2025 if (!rpc_IVelCtrl) { ok = false; break; }
2026 yCTrace(CONTROLBOARD, "getVelocityMove - cmd: %s", cmd.toString().c_str());
2027 ok = rpc_IVelCtrl->getRefVelocity(cmd.get(2).asInt32(), &dtmp);
2028
2029 response.addFloat64(dtmp);
2030 rec = true;
2031 } break;
2032
2034 if (!rpc_IVelCtrl) { ok = false; break; }
2035 yCTrace(CONTROLBOARD, "getVelocityMove_group - cmd: %s", cmd.toString().c_str());
2036
2037 int len = cmd.get(2).asInt32();
2038 Bottle& in = *(cmd.get(3).asList());
2039 int* jointList = new int[len];
2040 auto* refs = new double[len];
2041
2042 for (int j = 0; j < len; j++) {
2043 jointList[j] = in.get(j).asInt32();
2044 }
2046
2047 Bottle& b = response.addList();
2048 for (int i = 0; i < len; i++) {
2049 b.addFloat64(refs[i]);
2050 }
2051
2052 delete[] jointList;
2053 delete[] refs;
2054 } break;
2055
2056 case VOCAB_VELOCITY_MOVES: {
2057 if (!rpc_IVelCtrl) { ok = false; break; }
2058 yCTrace(CONTROLBOARD, "getVelocityMoves - cmd: %s", cmd.toString().c_str());
2059
2060 auto* refs = new double[controlledJoints];
2062 Bottle& b = response.addList();
2063 for (size_t i = 0; i < controlledJoints; i++) {
2064 b.addFloat64(refs[i]);
2065 }
2066 delete[] refs;
2067 } break;
2068
2069 case VOCAB_MOTORS_NUMBER: {
2070 if (!rpc_IMotor) { ok = false; break; }
2071 int tmp;
2073 response.addInt32(tmp);
2074 } break;
2075
2076 case VOCAB_AXES: {
2077 int tmp = 0;
2078 if (rpc_IPosCtrl) { ok = rpc_IPosCtrl->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2079 if (rpc_IVelCtrl) { ok = rpc_IVelCtrl->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2080 if (rpc_ITorque) { ok = rpc_ITorque->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2081 if (rpc_AxisInfo) { ok = rpc_AxisInfo->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2082 ok = false;
2083 } break;
2084
2085 case VOCAB_MOTION_DONE: {
2086 if (!rpc_IPosCtrl) { ok = false; break; }
2087 bool x = false;
2088 ;
2089 ok = rpc_IPosCtrl->checkMotionDone(cmd.get(2).asInt32(), &x);
2090 response.addInt32(x);
2091 } break;
2092
2094 if (!rpc_IPosCtrl) { ok = false; break; }
2095 bool x = false;
2096 int len = cmd.get(2).asInt32();
2097 Bottle& in = *(cmd.get(3).asList());
2098 int* jointList = new int[len];
2099 for (int j = 0; j < len; j++) {
2100 jointList[j] = in.get(j).asInt32();
2101 }
2102 if (rpc_IPosCtrl != nullptr) {
2103 ok = rpc_IPosCtrl->checkMotionDone(len, jointList, &x);
2104 }
2105 response.addInt32(x);
2106
2107 delete[] jointList;
2108 } break;
2109
2110 case VOCAB_MOTION_DONES: {
2111 if (!rpc_IPosCtrl) { ok = false; break; }
2112 bool x = false;
2113 ok = rpc_IPosCtrl->checkMotionDone(&x);
2114 response.addInt32(x);
2115 } break;
2116
2117 case VOCAB_REF_SPEED: {
2118 if (!rpc_IPosCtrl) { ok = false; break; }
2119 ok = rpc_IPosCtrl->getRefSpeed(cmd.get(2).asInt32(), &dtmp);
2120 response.addFloat64(dtmp);
2121 } break;
2122
2123 case VOCAB_REF_SPEED_GROUP: {
2124 if (!rpc_IPosCtrl) { ok = false; break; }
2125 int len = cmd.get(2).asInt32();
2126 Bottle& in = *(cmd.get(3).asList());
2127 int* jointList = new int[len];
2128 auto* speeds = new double[len];
2129
2130 for (int j = 0; j < len; j++) {
2131 jointList[j] = in.get(j).asInt32();
2132 }
2133 ok = rpc_IPosCtrl->getRefSpeeds(len, jointList, speeds);
2134
2135 Bottle& b = response.addList();
2136 for (int i = 0; i < len; i++) {
2137 b.addFloat64(speeds[i]);
2138 }
2139
2140 delete[] jointList;
2141 delete[] speeds;
2142 } break;
2143
2144 case VOCAB_REF_SPEEDS: {
2145 if (!rpc_IPosCtrl) { ok = false; break; }
2146 auto* p = new double[controlledJoints];
2147 ok = rpc_IPosCtrl->getRefSpeeds(p);
2148 Bottle& b = response.addList();
2149 for (size_t i = 0; i < controlledJoints; i++) {
2150 b.addFloat64(p[i]);
2151 }
2152 delete[] p;
2153 } break;
2154
2156 if (!rpc_IPosCtrl) { ok = false; break; }
2158 response.addFloat64(dtmp);
2159 } break;
2160
2162 if (!rpc_IPosCtrl) { ok = false; break; }
2163 int len = cmd.get(2).asInt32();
2164 Bottle& in = *(cmd.get(3).asList());
2165 int* jointList = new int[len];
2166 auto* accs = new double[len];
2167
2168 for (int j = 0; j < len; j++) {
2169 jointList[j] = in.get(j).asInt32();
2170 }
2172
2173 Bottle& b = response.addList();
2174 for (int i = 0; i < len; i++) {
2175 b.addFloat64(accs[i]);
2176 }
2177
2178 delete[] jointList;
2179 delete[] accs;
2180 } break;
2181
2183 if (!rpc_IPosCtrl) { ok = false; break; }
2184 auto* p = new double[controlledJoints];
2186 Bottle& b = response.addList();
2187 for (size_t i = 0; i < controlledJoints; i++) {
2188 b.addFloat64(p[i]);
2189 }
2190 delete[] p;
2191 } break;
2192
2193 case VOCAB_ENCODER: {
2194 if (!rpc_IEncTimed) { ok = false; break; }
2195 ok = rpc_IEncTimed->getEncoder(cmd.get(2).asInt32(), &dtmp);
2196 response.addFloat64(dtmp);
2197 } break;
2198
2199 case VOCAB_ENCODERS: {
2200 if (!rpc_IEncTimed) { ok = false; break; }
2201 auto* p = new double[controlledJoints];
2202 ok = rpc_IEncTimed->getEncoders(p);
2203 Bottle& b = response.addList();
2204 for (size_t i = 0; i < controlledJoints; i++) {
2205 b.addFloat64(p[i]);
2206 }
2207 delete[] p;
2208 } break;
2209
2210 case VOCAB_ENCODER_SPEED: {
2211 if (!rpc_IEncTimed) { ok = false; break; }
2212 ok = rpc_IEncTimed->getEncoderSpeed(cmd.get(2).asInt32(), &dtmp);
2213 response.addFloat64(dtmp);
2214 } break;
2215
2216 case VOCAB_ENCODER_SPEEDS: {
2217 if (!rpc_IEncTimed) { ok = false; break; }
2218 auto* p = new double[controlledJoints];
2220 Bottle& b = response.addList();
2221 for (size_t i = 0; i < controlledJoints; i++) {
2222 b.addFloat64(p[i]);
2223 }
2224 delete[] p;
2225 } break;
2226
2228 if (!rpc_IEncTimed) { ok = false; break; }
2230 response.addFloat64(dtmp);
2231 } break;
2232
2234 if (!rpc_IEncTimed) { ok = false; break; }
2235 auto* p = new double[controlledJoints];
2237 Bottle& b = response.addList();
2238 for (size_t i = 0; i < controlledJoints; i++) {
2239 b.addFloat64(p[i]);
2240 }
2241 delete[] p;
2242 } break;
2243
2244 case VOCAB_MOTOR_CPR: {
2245 if (!rpc_IMotEnc) { ok = false; break; }
2247 response.addFloat64(dtmp);
2248 } break;
2249
2250 case VOCAB_MOTOR_ENCODER: {
2251 if (!rpc_IMotEnc) { ok = false; break; }
2252 ok = rpc_IMotEnc->getMotorEncoder(cmd.get(2).asInt32(), &dtmp);
2253 response.addFloat64(dtmp);
2254 } break;
2255
2256 case VOCAB_MOTOR_ENCODERS: {
2257 if (!rpc_IMotEnc) { ok = false; break; }
2258 auto* p = new double[controlledJoints];
2260 Bottle& b = response.addList();
2261 for (size_t i = 0; i < controlledJoints; i++) {
2262 b.addFloat64(p[i]);
2263 }
2264 delete[] p;
2265 } break;
2266
2268 if (!rpc_IMotEnc) { ok = false; break; }
2270 response.addFloat64(dtmp);
2271 } break;
2272
2274 if (!rpc_IMotEnc) { ok = false; break; }
2275 auto* p = new double[controlledJoints];
2277 Bottle& b = response.addList();
2278 for (size_t i = 0; i < controlledJoints; i++) {
2279 b.addFloat64(p[i]);
2280 }
2281 delete[] p;
2282 } break;
2283
2285 if (!rpc_IMotEnc) { ok = false; break; }
2287 response.addFloat64(dtmp);
2288 } break;
2289
2291 auto* p = new double[controlledJoints];
2292 if (!rpc_IMotEnc) { ok = false; break; }
2294 Bottle& b = response.addList();
2295 for (size_t i = 0; i < controlledJoints; i++) {
2296 b.addFloat64(p[i]);
2297 }
2298 delete[] p;
2299 } break;
2300
2302 int num = 0;
2303 if (!rpc_IMotEnc) { ok = false; break; }
2305 response.addInt32(num);
2306 } break;
2307
2308 case VOCAB_AMP_CURRENT: {
2309 if (!rcp_IAmp) { ok = false; break; }
2310 ok = rcp_IAmp->getCurrent(cmd.get(2).asInt32(), &dtmp);
2311 response.addFloat64(dtmp);
2312 } break;
2313
2314 case VOCAB_AMP_CURRENTS: {
2315 if (!rcp_IAmp) { ok = false; break; }
2316 auto* p = new double[controlledJoints];
2317 ok = rcp_IAmp->getCurrents(p);
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
2325 case VOCAB_AMP_STATUS: {
2326 if (!rcp_IAmp) { ok = false; break; }
2327 int* p = new int[controlledJoints];
2328 ok = rcp_IAmp->getAmpStatus(p);
2329 Bottle& b = response.addList();
2330 for (size_t i = 0; i < controlledJoints; i++) {
2331 b.addInt32(p[i]);
2332 }
2333 delete[] p;
2334 } break;
2335
2337 int j = cmd.get(2).asInt32();
2338 int itmp;
2339 if (!rcp_IAmp) { ok = false; break; }
2340 ok = rcp_IAmp->getAmpStatus(j, &itmp);
2341 response.addInt32(itmp);
2342 } break;
2343
2345 int m = cmd.get(2).asInt32();
2346 if (!rcp_IAmp) { ok = false; break; }
2348 response.addFloat64(dtmp);
2349 } break;
2350
2352 int m = cmd.get(2).asInt32();
2353 if (!rcp_IAmp) { ok = false; break; }
2354 ok = rcp_IAmp->getPeakCurrent(m, &dtmp);
2355 response.addFloat64(dtmp);
2356 } break;
2357
2358 case VOCAB_AMP_PWM: {
2359 int m = cmd.get(2).asInt32();
2360 if (!rcp_IAmp) { ok = false; break; }
2361 ok = rcp_IAmp->getPWM(m, &dtmp);
2362 yCTrace(CONTROLBOARD) << "RPC parser::getPWM: j" << m << " val " << dtmp;
2363 response.addFloat64(dtmp);
2364 } break;
2365
2366 case VOCAB_AMP_PWM_LIMIT: {
2367 int m = cmd.get(2).asInt32();
2368 if (!rcp_IAmp) { ok = false; break; }
2369 ok = rcp_IAmp->getPWMLimit(m, &dtmp);
2370 response.addFloat64(dtmp);
2371 } break;
2372
2374 int m = cmd.get(2).asInt32();
2375 if (!rcp_IAmp) { ok = false; break; }
2377 response.addFloat64(dtmp);
2378 } break;
2379
2380 case VOCAB_LIMITS: {
2381 double min = 0.0;
2382 double max = 0.0;
2383 if (!rcp_Ilim) { ok = false; break; }
2384 ok = rcp_Ilim->getLimits(cmd.get(2).asInt32(), &min, &max);
2385 response.addFloat64(min);
2386 response.addFloat64(max);
2387 } break;
2388
2389 case VOCAB_VEL_LIMITS: {
2390 double min = 0.0;
2391 double max = 0.0;
2392 if (!rcp_Ilim) { ok = false; break; }
2393 ok = rcp_Ilim->getVelLimits(cmd.get(2).asInt32(), &min, &max);
2394 response.addFloat64(min);
2395 response.addFloat64(max);
2396 } break;
2397
2398 case VOCAB_INFO_NAME: {
2399 std::string name = "undocumented";
2400 if (!rpc_AxisInfo) { ok = false; break; }
2401 ok = rpc_AxisInfo->getAxisName(cmd.get(2).asInt32(), name);
2402 response.addString(name.c_str());
2403 } break;
2404
2405 case VOCAB_INFO_TYPE: {
2407 if (!rpc_AxisInfo) { ok = false; break; }
2408 ok = rpc_AxisInfo->getJointType(cmd.get(2).asInt32(), type);
2409 response.addInt32(type);
2410 } break;
2411
2412 default:
2413 {
2414 yCError(CONTROLBOARD, "received an unknown request after a VOCAB_GET: %s", yarp::os::Vocab32::decode(cmd.get(1).asVocab32()).c_str());
2415 } break;
2416 } //switch cmd.get(1).asVocab32())
2417
2419 appendTimeStamp(response, lastRpcStamp);
2420 } // case VOCAB_GET
2421 default:
2422 break;
2423 } //switch code
2424
2425 if (!rec) {
2426 ok = DeviceResponder::respond(cmd, response);
2427 }
2428 }
2429
2430 if (!ok) {
2431 // failed thus send only a VOCAB back.
2432 response.clear();
2433 response.addVocab32(VOCAB_FAILED);
2434 } else {
2435 response.addVocab32(VOCAB_OK);
2436 }
2437 }
2438 std::string ss = response.toString();
2439
2440 return ok;
2441}
2442
2444{
2445 bool ok = false;
2446 int tmp_axes = 0;
2447 if (rpc_IPosCtrl) { rpc_IPosCtrl->getAxes(&tmp_axes); ok = true; }
2448 else if (rpc_IVelCtrl) { rpc_IVelCtrl->getAxes(&tmp_axes); ok = true; }
2449 else if (rpc_ITorque) { rpc_ITorque->getAxes(&tmp_axes); ok = true; }
2450 else if (rpc_AxisInfo) { rpc_AxisInfo->getAxes(&tmp_axes); ok = true; }
2451 if (ok) { controlledJoints = static_cast<size_t>(tmp_axes); }
2452 else { yCError(CONTROLBOARD, "Unable to get number of joints"); return false; }
2453
2455 addUsage("[get] [axes]", "get the number of axes");
2456 addUsage("[get] [name] $iAxisNumber", "get a human-readable name for an axis, if available");
2457 addUsage("[set] [pos] $iAxisNumber $fPosition", "command the position of an axis");
2458 addUsage("[set] [rel] $iAxisNumber $fPosition", "command the relative position of an axis");
2459 addUsage("[set] [vmo] $iAxisNumber $fVelocity", "command the velocity of an axis");
2460 addUsage("[get] [enc] $iAxisNumber", "get the encoder value for an axis");
2461
2462 std::string args;
2463 for (size_t i = 0; i < controlledJoints; i++) {
2464 if (i > 0) {
2465 args += " ";
2466 }
2467 // removed dependency from yarp internals
2468 //args = args + "$f" + yarp::yarp::conf::numeric::to_string(i);
2469 }
2470 addUsage((std::string("[set] [poss] (") + args + ")").c_str(),
2471 "command the position of all axes");
2472 addUsage((std::string("[set] [rels] (") + args + ")").c_str(),
2473 "command the relative position of all axes");
2474 addUsage((std::string("[set] [vmos] (") + args + ")").c_str(),
2475 "command the velocity of all axes");
2476
2477 addUsage("[set] [aen] $iAxisNumber", "enable (amplifier for) the given axis");
2478 addUsage("[set] [adi] $iAxisNumber", "disable (amplifier for) the given axis");
2479 addUsage("[get] [acu] $iAxisNumber", "get current for the given axis");
2480 addUsage("[get] [acus]", "get current for all axes");
2481
2482 return ok;
2483}
2484
2486{
2487 x->view(rpc_IPid);
2488 x->view(rpc_IPosCtrl);
2489 x->view(rpc_IPosDirect);
2490 x->view(rpc_IVelCtrl);
2491 x->view(rpc_IEncTimed);
2492 x->view(rpc_IMotEnc);
2493 x->view(rpc_IMotor);
2494 x->view(rpc_IVar);
2495 x->view(rcp_IAmp);
2496 x->view(rcp_Ilim);
2497 x->view(rpc_AxisInfo);
2499 x->view(rpc_Icalib);
2500 x->view(rpc_IImpedance);
2501 x->view(rpc_ITorque);
2502 x->view(rpc_iCtrlMode);
2503 x->view(rpc_IInteract);
2504 x->view(rpc_ICurrent);
2505 x->view(rpc_IPWM);
2507 controlledJoints = 0;
2508}
2509
2511{
2512 rpc_IPid = nullptr;
2513 rpc_IPosCtrl = nullptr;
2514 rpc_IPosDirect = nullptr;
2515 rpc_IVelCtrl = nullptr;
2516 rpc_IEncTimed = nullptr;
2517 rpc_IMotEnc = nullptr;
2518 rpc_IMotor = nullptr;
2519 rpc_IVar = nullptr;
2520 rcp_IAmp = nullptr;
2521 rcp_Ilim = nullptr;
2522 rpc_AxisInfo = nullptr;
2523 rpc_IRemoteCalibrator = nullptr;
2524 rpc_Icalib = nullptr;
2525 rpc_IImpedance = nullptr;
2526 rpc_ITorque = nullptr;
2527 rpc_iCtrlMode = nullptr;
2528 rpc_IInteract = nullptr;
2529 rpc_ICurrent = nullptr;
2530 rpc_IPWM = nullptr;
2531 rpc_IJointFault = nullptr;
2532 controlledJoints = 0;
2533}
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_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_POSITION_MOVE
constexpr yarp::conf::vocab32_t VOCAB_REF_ACCELERATION
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
FeatureMode mode
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
constexpr yarp::conf::vocab32_t VOCAB_VELOCITY_MOVE_GROUP
constexpr yarp::conf::vocab32_t VOCAB_VELOCITY_MOVES
void appendTimeStamp(Bottle &bot, Stamp &st)
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 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.
double kd
derivative gain
double scale
scale for the pid output
double offset
pwm offset added to the pid output
double stiction_down_val
down stiction offset added to the pid output
double stiction_up_val
up stiction offset added to the pid output
double max_output
max output
double kff
feedforward gain
double ki
integrative gain
double max_int
saturation threshold for the integrator
double kp
proportional gain
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:65
void add(const Value &value)
Add a Value to the bottle, at the end of the list.
Definition Bottle.cpp:315
void addVocab32(yarp::conf::vocab32_t x)
Places a 32 bit 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:188
size_type size() const
Gets the number of elements in the bottle.
Definition Bottle.cpp:257
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:252
Bottle tail() const
Get all but the first element of a bottle.
Definition Bottle.cpp:367
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:176
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition Bottle.cpp:217
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:228
virtual yarp::conf::vocab32_t asVocab32() const
Get 32 bit vocabulary identifier as an integer.
Definition Value.cpp:234
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition Value.cpp:210
virtual Bottle * asList() const
Get list value.
Definition Value.cpp:252
virtual std::string asString() const
Get string value.
Definition Value.cpp:246
void resize(size_t size) override
Resize the vector.
Definition Vector.h:211
#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.
PidControlTypeEnum
Definition PidEnums.h:15
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
Definition Vocab32.cpp:33
An interface to the operating system, including Port based communication.