YARP
Yet Another Robot Platform
ControlBoardWrapper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * Copyright (C) 2006-2010 RobotCub Consortium
4  * All rights reserved.
5  *
6  * This software may be modified and distributed under the terms of the
7  * BSD-3-Clause license. See the accompanying LICENSE file for details.
8  */
9 
10 #include "ControlBoardWrapper.h"
11 
12 #include <yarp/os/LogComponent.h>
13 #include <yarp/os/LogStream.h>
14 
16 
18 #include "RPCMessagesParser.h"
20 #include <algorithm>
21 #include <cstring> // for memset function
22 #include <iostream>
23 #include <numeric>
24 #include <sstream>
25 
26 using namespace yarp::os;
27 using namespace yarp::dev;
28 using namespace yarp::dev::impl;
29 using namespace yarp::sig;
30 using namespace std;
31 
32 
34  yarp::os::PeriodicThread(default_period),
35  ownDevices(true)
36 {
37  streaming_parser.init(this);
38  RPC_parser.init(this);
39 }
40 
41 void ControlBoardWrapper::cleanup_yarpPorts()
42 {
43  //shut down control port
44  inputRPCPort.interrupt();
45  inputRPCPort.removeCallbackLock();
46  inputRPCPort.close();
47 
48  inputStreamingPort.interrupt();
49  inputStreamingPort.close();
50 
51  outputPositionStatePort.interrupt();
52  outputPositionStatePort.close();
53 
54  extendedOutputStatePort.interrupt();
55  extendedOutputStatePort.close();
56 
57  rpcData.destroy();
58 }
59 
61 
63 {
64  //stop thread if running
65  detachAll();
66 
69  }
70 
71  if (useROS != ROS_only) {
72  cleanup_yarpPorts();
73  }
74 
75  if (rosNode != nullptr) {
76  delete rosNode;
77  rosNode = nullptr;
78  }
79 
80  //if we own a deviced we have to close and delete it
81  if (ownDevices) {
82  // we should have created a new devices which we need to delete
83  if (subDeviceOwned != nullptr) {
84  subDeviceOwned->close();
85  delete subDeviceOwned;
86  subDeviceOwned = nullptr;
87  }
88  } else {
89  detachAll();
90  }
91  return true;
92 }
93 
94 bool ControlBoardWrapper::checkPortName(Searchable& params)
95 {
96  /* see if rootName is present in the config file, this param is not used from long time, so it'll be
97  * marked as deprecated.
98  */
99  if (params.check("rootName")) {
101  "************************************************************************************\n"
102  "* controlboardwrapper2 is using the deprecated parameter 'rootName' for port name, *\n"
103  "* It has to be removed and substituted with: *\n"
104  "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
105  "************************************************************************************";
106  rootName = params.find("rootName").asString();
107  }
108 
109  // find name as port name (similar both in new and old policy
110  if (!params.check("name")) {
112  "************************************************************************************\n"
113  "* controlboardwrapper2 missing mandatory parameter 'name' for port name, usage is: *\n"
114  "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
115  "************************************************************************************";
116  return false;
117  }
118 
119  partName = params.find("name").asString();
120  if (partName[0] != '/') {
122  "************************************************************************************\n"
123  "* controlboardwrapper2 'name' parameter for port name does not follow convention, *\n"
124  "* it MUST start with a leading '/' since it is used as the full prefix port name *\n"
125  "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
126  "* A temporary automatic fix will be done for you, but please fix your config file *\n"
127  "************************************************************************************";
128  rootName = "/" + partName;
129  } else {
130  rootName = partName;
131  }
132 
133  return true;
134 }
135 
136 bool ControlBoardWrapper::checkROSParams(Searchable& config)
137 {
138  // check for ROS parameter group
139  if (!config.check("ROS")) {
140  useROS = ROS_disabled;
141  return true;
142  }
143 
144  yCInfo(CONTROLBOARDWRAPPER) << "ROS group was FOUND in config file.";
145 
146  Bottle& rosGroup = config.findGroup("ROS");
147  if (rosGroup.isNull()) {
148  yCError(CONTROLBOARDWRAPPER) << partName << "ROS group params is not a valid group or empty";
149  useROS = ROS_config_error;
150  return false;
151  }
152 
153  // check for useROS parameter
154  if (!rosGroup.check("useROS")) {
155  yCError(CONTROLBOARDWRAPPER) << partName << " cannot find useROS parameter, mandatory when using ROS message. \n \
156  Allowed values are true, false, ROS_only";
157  useROS = ROS_config_error;
158  return false;
159  }
160  std::string ros_use_type = rosGroup.find("useROS").asString();
161  if (ros_use_type == "false") {
162  yCInfo(CONTROLBOARDWRAPPER) << partName << "useROS topic if set to 'false'";
163  useROS = ROS_disabled;
164  return true;
165  }
166 
167  if (ros_use_type == "true") {
168  yCInfo(CONTROLBOARDWRAPPER) << partName << "useROS topic if set to 'true'";
169  useROS = ROS_enabled;
170  } else if (ros_use_type == "only") {
171  yCInfo(CONTROLBOARDWRAPPER) << partName << "useROS topic if set to 'only";
172  useROS = ROS_only;
173  } else {
174  yCInfo(CONTROLBOARDWRAPPER) << partName << "useROS parameter is seet to unvalid value ('" << ros_use_type << "'), supported values are 'true', 'false', 'only'";
175  useROS = ROS_config_error;
176  return false;
177  }
178 
179  // check for ROS_nodeName parameter
180  if (!rosGroup.check("ROS_nodeName")) {
181  yCError(CONTROLBOARDWRAPPER) << partName << " cannot find ROS_nodeName parameter, mandatory when using ROS message";
182  useROS = ROS_config_error;
183  return false;
184  }
185  rosNodeName = rosGroup.find("ROS_nodeName").asString(); // TODO: check name is correct
186  yCInfo(CONTROLBOARDWRAPPER) << partName << "rosNodeName is " << rosNodeName;
187 
188  // check for ROS_topicName parameter
189  if (!rosGroup.check("ROS_topicName")) {
190  yCError(CONTROLBOARDWRAPPER) << partName << " cannot find rosTopicName parameter, mandatory when using ROS message";
191  useROS = ROS_config_error;
192  return false;
193  }
194  rosTopicName = rosGroup.find("ROS_topicName").asString();
195  yCInfo(CONTROLBOARDWRAPPER) << partName << "rosTopicName is " << rosTopicName;
196 
197  // check for rosNodeName parameter
198  // UPDATE: joint names are got from MotionControl subdevice now.
199  // An error should be thrown later on in case we fail getting names from device
200  if (!rosGroup.check("jointNames")) {
201  yCInfo(CONTROLBOARDWRAPPER) << partName << "ROS topic has been required, jointNames will be got from motionControl subdevice.";
202  } else // if names are there, store them. They will be used for back compatibility if old policy is used.
203  {
204  Bottle nameList = rosGroup.findGroup("jointNames").tail();
205  if (nameList.isNull()) {
206  yCError(CONTROLBOARDWRAPPER) << partName << " jointNames not found";
207  useROS = ROS_config_error;
208  return false;
209  }
210 
211  if (nameList.size() != static_cast<size_t>(controlledJoints)) {
212  yCError(CONTROLBOARDWRAPPER) << partName << " jointNames incorrect number of entries. \n jointNames is " << nameList.toString() << "while expected length is " << controlledJoints;
213  useROS = ROS_config_error;
214  return false;
215  }
216 
217  jointNames.clear();
218  for (size_t i = 0; i < controlledJoints; i++) {
219  jointNames.push_back(nameList.get(i).toString());
220  }
221  }
222  return true;
223 }
224 
225 bool ControlBoardWrapper::initialize_ROS()
226 {
227  bool success = false;
228  switch (useROS) {
229  case ROS_enabled:
230  case ROS_only: {
231  rosNode = new yarp::os::Node(rosNodeName); // add a ROS node
232 
233  if (rosNode == nullptr) {
234  yCError(CONTROLBOARDWRAPPER) << " opening " << rosNodeName << " Node, check your yarp-ROS network configuration";
235  success = false;
236  break;
237  }
238 
239  if (!rosPublisherPort.topic(rosTopicName)) {
240  yCError(CONTROLBOARDWRAPPER) << " opening " << rosTopicName << " Topic, check your yarp-ROS network configuration";
241  success = false;
242  break;
243  }
244  success = true;
245  } break;
246 
247  case ROS_disabled: {
248  yCInfo(CONTROLBOARDWRAPPER) << partName << ": no ROS initialization required";
249  success = true;
250  } break;
251 
252  case ROS_config_error: {
253  yCError(CONTROLBOARDWRAPPER) << partName << " ROS parameter are not correct, check your configuration file";
254  success = false;
255  } break;
256 
257  default:
258  {
259  yCError(CONTROLBOARDWRAPPER) << partName << " something went wrong with ROS configuration, we should never be here!!!";
260  success = false;
261  } break;
262  }
263  return success;
264 }
265 
266 bool ControlBoardWrapper::initialize_YARP(yarp::os::Searchable& prop)
267 {
268  bool success = false;
269 
270  switch (useROS) {
271  case ROS_only: {
272  yCInfo(CONTROLBOARDWRAPPER) << partName << " No YARP initialization required";
273  success = true;
274  } break;
275 
276  default:
277  {
278  yCInfo(CONTROLBOARDWRAPPER) << partName << " initting YARP initialization";
279  // initialize callback
280  if (!streaming_parser.initialize()) {
281  yCError(CONTROLBOARDWRAPPER) << "Error could not initialize callback object";
282  success = false;
283  break;
284  }
285 
286  rootName = prop.check("rootName", Value("/"), "starting '/' if needed.").asString();
287  partName = prop.check("name", Value("controlboard"), "prefix for port names").asString();
288  rootName += (partName);
289  if (rootName.find("//") != std::string::npos) {
290  rootName.replace(rootName.find("//"), 2, "/");
291  }
292 
294  if (!inputRPCPort.open((rootName + "/rpc:i"))) {
295  yCError(CONTROLBOARDWRAPPER) << "Error opening port " << rootName + "/rpc:i";
296  success = false;
297  break;
298  }
299  inputRPCPort.setReader(RPC_parser);
300  inputRPC_buffer.attach(inputRPCPort);
301  RPC_parser.attach(inputRPC_buffer);
302 
303  if (!inputStreamingPort.open(rootName + "/command:i")) {
304  yCError(CONTROLBOARDWRAPPER) << "Error opening port " << rootName + "/rpc:i";
305  success = false;
306  break;
307  }
308 
309  // attach callback.
310  inputStreamingPort.setStrict();
311  inputStreamingPort.useCallback(streaming_parser);
312 
313  if (!outputPositionStatePort.open(rootName + "/state:o")) {
314  yCError(CONTROLBOARDWRAPPER) << "Error opening port " << rootName + "/state:o";
315  success = false;
316  break;
317  }
318 
319  // new extended output state port
320  if (!extendedOutputStatePort.open(rootName + "/stateExt:o")) {
321  yCError(CONTROLBOARDWRAPPER) << "Error opening port " << rootName + "/state:o";
322  success = false;
323  break;
324  }
325  extendedOutputState_buffer.attach(extendedOutputStatePort);
326  success = true;
327  } break;
328  } // end switch
329 
330  // cleanup if something went wrong
331  if (!success) {
332  cleanup_yarpPorts();
333  }
334  return success;
335 }
336 
337 
339 {
340  Property prop;
341  prop.fromString(config.toString());
342 
343  if (prop.check("verbose", "Deprecated flag. Use log components instead")) {
344  yCWarning(CONTROLBOARDWRAPPER) << "'verbose' flag is deprecated. Use log components instead";
345  }
346 
347  if (!checkPortName(config)) {
348  yCError(CONTROLBOARDWRAPPER) << "'portName' was not correctly set, check you r configuration file";
349  return false;
350  }
351 
352  // check FIRST for deprecated parameter
353  if (prop.check("threadrate")) {
354  yCError(CONTROLBOARDWRAPPER) << "Using removed parameter 'threadrate', use 'period' instead";
355  return false;
356  }
357 
358  // NOW, check for correct parameter, so if both are present we use the correct one
359  if (prop.check("period")) {
360  if (!prop.find("period").isInt32()) {
361  yCError(CONTROLBOARDWRAPPER) << "'period' parameter is not an integer value";
362  return false;
363  }
364  period = prop.find("period").asInt32() / 1000.0;
365  if (period <= 0) {
366  yCError(CONTROLBOARDWRAPPER) << "'period' parameter is not valid, read value is" << period;
367  return false;
368  }
369  } else {
370  yCDebug(CONTROLBOARDWRAPPER) << "'period' parameter missing, using default thread period = 20ms";
371  period = default_period;
372  }
373 
374  // check if we need to create subdevice or if they are
375  // passed later on thorugh attachAll()
376  if (prop.check("subdevice")) {
377  ownDevices = true;
378  prop.setMonitor(config.getMonitor());
379  if (!openAndAttachSubDevice(prop)) {
380  yCError(CONTROLBOARDWRAPPER, "Error while opening subdevice");
381  return false;
382  }
383  } else {
384  ownDevices = false;
385  if (!openDeferredAttach(prop)) {
386  return false;
387  }
388  }
389 
390  // using controlledJoints here will allocate more memory than required, but not so much.
392 
393  /* This must be after the openAndAttachSubDevice() or openDeferredAttach() in order to have the correct number of controlledJoints,
394  but before the initialize_ROS and initialize_YARP */
395  if (!checkROSParams(config)) {
396  yCError(CONTROLBOARDWRAPPER) << partName << " ROS parameter are not correct, check your configuration file";
397  return false;
398  }
399 
400  // call ROS node/topic initialization, if needed
401  if (!initialize_ROS()) {
402  return false;
403  }
404 
405  // call YARP port initialization, if needed
406  if (!initialize_YARP(prop)) {
407  yCError(CONTROLBOARDWRAPPER) << partName << "Something wrong when initting yarp ports";
408  return false;
409  }
410 
411  times.resize(controlledJoints);
412  ros_struct.name.resize(controlledJoints);
413  ros_struct.position.resize(controlledJoints);
414  ros_struct.velocity.resize(controlledJoints);
415  ros_struct.effort.resize(controlledJoints);
416 
417  // In case attach is not deferred and the controlboard already owns a valid device
418  // we can start the thread. Otherwise this will happen when attachAll is called
419  if (ownDevices) {
420  PeriodicThread::setPeriod(period);
421  if (!PeriodicThread::start()) {
422  return false;
423  }
424  }
425  return true;
426 }
427 
428 
429 // Default usage
430 // Open the wrapper only, the attach method needs to be called before using it
431 bool ControlBoardWrapper::openDeferredAttach(Property& prop)
432 {
433  if (!prop.check("networks", "list of networks merged by this wrapper")) {
434  yCError(CONTROLBOARDWRAPPER) << "List of networks to attach to was not found.";
435  return false;
436  }
437 
438  Bottle* nets = prop.find("networks").asList();
439  if (nets == nullptr) {
440  yCError(CONTROLBOARDWRAPPER) << "Error parsing parameters: \"networks\" should be followed by a list";
441  return false;
442  }
443 
444  if (!prop.check("joints", "number of joints of the part")) {
445  return false;
446  }
447 
448  controlledJoints = prop.find("joints").asInt32();
449 
450  size_t nsubdevices = nets->size();
451  device.lut.resize(controlledJoints);
452  device.subdevices.resize(nsubdevices);
453 
454  // configure the devices
455  size_t totalJ = 0;
456  for (size_t k = 0; k < nets->size(); k++) {
457  Bottle parameters;
458  size_t wBase;
459  size_t wTop;
460  size_t base;
461  size_t top;
462 
463  parameters = prop.findGroup(nets->get(k).asString());
464 
465  if (parameters.size() == 2) {
466  Bottle* bot = parameters.get(1).asList();
467  Bottle tmpBot;
468  if (bot == nullptr) {
469  // probably data are not passed in the correct way, try to read them as a string.
470  std::string bString(parameters.get(1).asString());
471  tmpBot.fromString(bString);
472 
473  if (tmpBot.size() != 4) {
474  yCError(CONTROLBOARDWRAPPER) << "Error: check network parameters in part description"
475  << "--> I was expecting " << nets->get(k).asString() << " followed by a list of four integers in parenthesis"
476  << "Got: " << parameters.toString();
477  return false;
478  }
479 
480  bot = &tmpBot;
481  }
482 
483  // If I came here, bot is correct
484  wBase = static_cast<size_t>(bot->get(0).asInt32());
485  wTop = static_cast<size_t>(bot->get(1).asInt32());
486  base = static_cast<size_t>(bot->get(2).asInt32());
487  top = static_cast<size_t>(bot->get(3).asInt32());
488  } else if (parameters.size() == 5) {
489  yCError(CONTROLBOARDWRAPPER) << "Parameter networks use deprecated syntax";
490  wBase = static_cast<size_t>(parameters.get(1).asInt32());
491  wTop = static_cast<size_t>(parameters.get(2).asInt32());
492  base = static_cast<size_t>(parameters.get(3).asInt32());
493  top = static_cast<size_t>(parameters.get(4).asInt32());
494  } else {
495  yCError(CONTROLBOARDWRAPPER) << "Error: check network parameters in part description"
496  << "--> I was expecting " << nets->get(k).asString() << " followed by a list of four integers in parenthesis"
497  << "Got: " << parameters.toString();
498  return false;
499  }
500 
501  SubDevice* tmpDevice = device.getSubdevice(k);
502  if (!tmpDevice) {
503  yCError(CONTROLBOARDWRAPPER) << "Get of subdevice returned null";
504  return false;
505  }
506 
507  size_t axes = top - base + 1;
508  if (!tmpDevice->configure(wBase, wTop, base, top, axes, nets->get(k).asString(), this)) {
509  yCError(CONTROLBOARDWRAPPER) << "Configure of subdevice ret false";
510  return false;
511  }
512 
513  // Check input values are in range
514  if ((wBase == static_cast<size_t>(-1)) || (wBase >= controlledJoints)) {
515  yCError(CONTROLBOARDWRAPPER) << "Input configuration for device " << partName << "has a wrong attach map."
516  << "First index " << wBase << "must be inside range from 0 to 'joints' (" << controlledJoints << ")";
517  return false;
518  }
519 
520  if ((wTop == static_cast<size_t>(-1)) || (wTop >= controlledJoints)) {
521  yCError(CONTROLBOARDWRAPPER) << "Input configuration for device " << partName << "has a wrong attach map."
522  << "Second index " << wTop << "must be inside range from 0 to 'joints' (" << controlledJoints << ")";
523  return false;
524  }
525 
526  if (wBase > wTop) {
527  yCError(CONTROLBOARDWRAPPER) << "Input configuration for device " << partName << "has a wrong attach map."
528  << "First index " << wBase << "must be lower than second index " << wTop;
529  return false;
530  }
531 
532  for (size_t j = wBase, jInDev = base; j <= wTop; j++, jInDev++) {
533  device.lut[j].deviceEntry = k;
534  device.lut[j].offset = static_cast<int>(j - wBase);
535  device.lut[j].jointIndexInDev = jInDev;
536  }
537 
538  totalJ += axes;
539  }
540 
541  if (totalJ != controlledJoints) {
542  yCError(CONTROLBOARDWRAPPER) << "Error total number of mapped joints (" << totalJ << ") does not correspond to part joints (" << controlledJoints << ")";
543  return false;
544  }
545  return true;
546 }
547 
548 // For the simulator, if a subdevice parameter is given to the wrapper, it will
549 // open it and attach to immediately.
550 bool ControlBoardWrapper::openAndAttachSubDevice(Property& prop)
551 {
552  Property p;
553  subDeviceOwned = new PolyDriver;
554  p.fromString(prop.toString());
555 
556  std::string subdevice = prop.find("subdevice").asString();
557  p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring
558  p.unput("device");
559  p.put("device", subdevice); // subdevice was already checked before
560 
561  // if errors occurred during open, quit here.
562  yCDebug(CONTROLBOARDWRAPPER, "opening subdevice");
563  subDeviceOwned->open(p);
564 
565  if (!subDeviceOwned->isValid()) {
566  yCError(CONTROLBOARDWRAPPER, "opening subdevice... FAILED");
567  return false;
568  }
569 
570  yarp::dev::IEncoders* iencs = nullptr;
571 
572  subDeviceOwned->view(iencs);
573 
574  if (iencs == nullptr) {
575  yCError(CONTROLBOARDWRAPPER, "Opening IEncoders interface of subdevice... FAILED");
576  return false;
577  }
578 
579  int tmp_axes;
580  bool getAx = iencs->getAxes(&tmp_axes);
581 
582  if (!getAx) {
583  yCError(CONTROLBOARDWRAPPER, "Calling getAxes of subdevice... FAILED");
584  return false;
585  }
586  controlledJoints = static_cast<size_t>(tmp_axes);
587 
588  yCDebug(CONTROLBOARDWRAPPER, "Joints parameter is %zu", controlledJoints);
589 
590 
591  device.lut.resize(controlledJoints);
592  device.subdevices.resize(1);
593 
594  // configure the device
595  size_t base = 0;
596  size_t top = controlledJoints - 1;
597 
598  size_t wbase = base;
599  size_t wtop = top;
600  SubDevice* tmpDevice = device.getSubdevice(0);
601 
602  std::string subDevName((partName + "_" + subdevice));
603  if (!tmpDevice->configure(wbase, wtop, base, top, controlledJoints, subDevName, this)) {
604  yCError(CONTROLBOARDWRAPPER) << "Configure of subdevice ret false";
605  return false;
606  }
607 
608  for (size_t j = 0; j < controlledJoints; j++) {
609  device.lut[j].deviceEntry = 0;
610  device.lut[j].offset = j;
611  }
612 
613 
614  if (!device.subdevices[0].attach(subDeviceOwned, subDevName)) {
615  return false;
616  }
617 
618  // initialization.
619  RPC_parser.initialize();
620  updateAxisName();
621  calculateMaxNumOfJointsInDevices();
622  return true;
623 }
624 
625 void ControlBoardWrapper::calculateMaxNumOfJointsInDevices()
626 {
628 
629  for (size_t d = 0; d < device.subdevices.size(); d++) {
630  SubDevice* p = device.getSubdevice(d);
633  }
634  }
635 }
636 
637 bool ControlBoardWrapper::updateAxisName()
638 {
639  // If attached device has axisName update the internal values, otherwise keep the on from wrapper
640  // config file, if any.
641  // IMPORTANT!! This function has to be called BEFORE the thread starts, because if ROS is enabled,
642  // the name has to be correct right from the first message!!
643 
644  // FOR THE FUTURE: this double version will be dropped because it'll create confusion. Only the names
645  // from the motionControl device will be considered good
646 
647  // no need to update this variable if we are not using ROS. Yarp RPC will always call the sudevice.
648  if (useROS == ROS_disabled) {
649  return true;
650  }
651 
652  std::string tmp;
653  // I need a temporary vector because if I'm wrapping more than one subdevice, and one of them
654  // does not have the axesName, then I'd stick with the old names from wrpper config file, if any.
655  vector<string> tmpVect;
656  bool ret = true;
657 
658  tmpVect.clear();
659  for (size_t i = 0; i < controlledJoints; i++) {
660  if ((ret = getAxisName(i, tmp) && ret)) {
661  std::string tmp2(tmp);
662  tmpVect.push_back(tmp2);
663  }
664  }
665 
666  if (ret) {
667  if (!jointNames.empty()) {
668  yCWarning(CONTROLBOARDWRAPPER) << "Found 2 instance of jointNames parameter: one in the wrapper [ROS] group and another one in the subdevice, the latter one will be used.";
669  std::string fullNames;
670  for (size_t i = 0; i < controlledJoints; i++) {
671  fullNames.append(tmpVect[i]);
672  }
673  }
674 
675  jointNames.clear();
676  jointNames = tmpVect;
677  } else {
678  if (jointNames.empty()) {
679  yCError(CONTROLBOARDWRAPPER) << "Joint names were not found! they are mandatory when using ROS topic";
680  return false;
681  }
682 
683  yCWarning(CONTROLBOARDWRAPPER) << "\n" <<
684  "************************************************************************************************** \n" <<
685  "* Joint names for ROS topic were found in the [ROS] group in the wrapper config file for\n" <<
686  "* '" << partName << "' device.\n" <<
687  "* They should be in the MotionControl device(s) instead. Please update the config files.\n" <<
688  "**************************************************************************************************";
689  }
690  return true;
691 }
692 
693 
695 {
696  //check if we already instantiated a subdevice previously
697  if (ownDevices) {
698  return false;
699  }
700 
701  for (int p = 0; p < polylist.size(); p++) {
702  // look if we have to attach to a calibrator
703  std::string tmpKey = polylist[p]->key;
704  if (tmpKey == "Calibrator" || tmpKey == "calibrator") {
705  // Set the IRemoteCalibrator interface, the wrapper must point to the calibrato rdevice
706  yarp::dev::IRemoteCalibrator* calibrator;
707  polylist[p]->poly->view(calibrator);
708 
709  IRemoteCalibrator::setCalibratorDevice(calibrator);
710  continue;
711  }
712 
713  // find appropriate entry in list of subdevices and attach
714  size_t k = 0;
715  for (k = 0; k < device.subdevices.size(); k++) {
716  if (device.subdevices[k].id == tmpKey) {
717  if (!device.subdevices[k].attach(polylist[p]->poly, tmpKey)) {
718  yCError(CONTROLBOARDWRAPPER, "Attach to subdevice %s failed", polylist[p]->key.c_str());
719  return false;
720  }
721  }
722  }
723  }
724 
725  //check if all devices are attached to the driver
726  bool ready = true;
727  for (auto& subdevice : device.subdevices) {
728  if (!subdevice.isAttached()) {
729  yCError(CONTROLBOARDWRAPPER, "Device %s was not found in the list passed to attachAll", subdevice.id.c_str());
730  ready = false;
731  }
732  }
733 
734  if (!ready) {
735  yCError(CONTROLBOARDWRAPPER, "AttachAll failed, some subdevice was not found or its attach failed");
736  stringstream ss;
737  for (int p = 0; p < polylist.size(); p++) {
738  ss << polylist[p]->key.c_str() << " ";
739  }
740  yCError(CONTROLBOARDWRAPPER, "List of devices keys passed to attachAll: %s", ss.str().c_str());
741  return false;
742  }
743 
744  // initialization.
745  RPC_parser.initialize();
746 
747  updateAxisName();
748  calculateMaxNumOfJointsInDevices();
749  PeriodicThread::setPeriod(period);
750  return PeriodicThread::start();
751 }
752 
754 {
755  //check if we already instantiated a subdevice previously
756  if (ownDevices) {
757  return false;
758  }
759 
762  }
763 
764  int devices = device.subdevices.size();
765 
766  for (int k = 0; k < devices; k++) {
767  SubDevice* sub = device.getSubdevice(k);
768  if (sub) {
769  sub->detach();
770  }
771  }
772 
773  IRemoteCalibrator::releaseCalibratorDevice();
774  return true;
775 }
776 
778 {
779  // check we are not overflowing with input messages
780  if (inputStreamingPort.getPendingReads() >= 20) {
781  yCWarning(CONTROLBOARDWRAPPER) << "Number of streaming intput messages to be read is " << inputStreamingPort.getPendingReads() << " and can overflow";
782  }
783 
784  // Small optimization: Avoid to call getEncoders twice, one for YARP port
785  // and again for ROS topic.
786  //
787  // Calling getStuff here on ros_struct because it is a class member, hence
788  // always available. In the other side, to have the yarp struct to write into
789  // it will be rewuired to call port.prepare, that it is something I should
790  // not do if the wrapper is in ROS_only configuration.
791 
792  bool positionsOk = getEncodersTimed(ros_struct.position.data(), times.data());
793  bool speedsOk = getEncoderSpeeds(ros_struct.velocity.data());
794  bool torqueOk = getTorques(ros_struct.effort.data());
795 
796  // Update the port envelope time by averaging all timestamps
797  timeMutex.lock();
798  time.update(std::accumulate(times.begin(), times.end(), 0.0) / controlledJoints);
799  yarp::os::Stamp averageTime = time;
800  timeMutex.unlock();
801 
802  if (useROS != ROS_only) {
803  // handle stateExt first
804  jointData& yarp_struct = extendedOutputState_buffer.get();
805 
812  yarp_struct.torque.resize(controlledJoints);
813  yarp_struct.pwmDutycycle.resize(controlledJoints);
814  yarp_struct.current.resize(controlledJoints);
815  yarp_struct.controlMode.resize(controlledJoints);
817 
818  // Get already stored data from before. This is to avoid a double call to HW device,
819  // which may require more time. //
820  yarp_struct.jointPosition_isValid = positionsOk;
821  std::copy(ros_struct.position.begin(), ros_struct.position.end(), yarp_struct.jointPosition.begin());
822 
823  yarp_struct.jointVelocity_isValid = speedsOk;
824  std::copy(ros_struct.velocity.begin(), ros_struct.velocity.end(), yarp_struct.jointVelocity.begin());
825 
826  yarp_struct.torque_isValid = torqueOk;
827  std::copy(ros_struct.effort.begin(), ros_struct.effort.end(), yarp_struct.torque.begin());
828 
829  // Get remaining data from HW
831  yarp_struct.motorPosition_isValid = getMotorEncoders(yarp_struct.motorPosition.data());
832  yarp_struct.motorVelocity_isValid = getMotorEncoderSpeeds(yarp_struct.motorVelocity.data());
834  yarp_struct.torque_isValid = getTorques(yarp_struct.torque.data());
835  yarp_struct.pwmDutycycle_isValid = getDutyCycles(yarp_struct.pwmDutycycle.data());
837  yarp_struct.controlMode_isValid = getControlModes(yarp_struct.controlMode.data());
838  yarp_struct.interactionMode_isValid = getInteractionModes(reinterpret_cast<yarp::dev::InteractionModeEnum*>(yarp_struct.interactionMode.data()));
839 
840  extendedOutputStatePort.setEnvelope(averageTime);
841  extendedOutputState_buffer.write();
842 
843  // handle state:o
844  yarp::sig::Vector& v = outputPositionStatePort.prepare();
846  std::copy(yarp_struct.jointPosition.begin(), yarp_struct.jointPosition.end(), v.begin());
847 
848  outputPositionStatePort.setEnvelope(averageTime);
849  outputPositionStatePort.write();
850  }
851 
852  if (useROS != ROS_disabled) {
853  // Data from HW have been gathered few lines before
854  JointTypeEnum jType;
855  for (size_t i = 0; i < controlledJoints; i++) {
856  getJointType(i, jType);
857  if (jType == VOCAB_JOINTTYPE_REVOLUTE) {
858  ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]);
859  ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]);
860  }
861  }
862 
863  ros_struct.name = jointNames;
864 
865  ros_struct.header.seq = rosMsgCounter++;
866  ros_struct.header.stamp = averageTime.getTime();
867 
868  rosPublisherPort.write(ros_struct);
869  }
870 }
ControlBoardWrapperCommon::rpcData
MultiJointData rpcData
Definition: ControlBoardWrapperCommon.h:28
yarp::os::Port::close
void close() override
Stop port activity.
Definition: Port.cpp:357
LogStream.h
ControlBoardWrapperAxisInfo::getAxisName
bool getAxisName(int j, std::string &name) override
Definition: ControlBoardWrapperAxisInfo.cpp:14
ControlBoardWrapperCommon::time
yarp::os::Stamp time
Definition: ControlBoardWrapperCommon.h:31
yarp::dev::impl::jointData::current_isValid
bool current_isValid
Definition: jointData.h:49
yarp::dev::impl::jointData::controlMode
yarp::sig::VectorOf< int > controlMode
Definition: jointData.h:50
ROS_only
@ ROS_only
Definition: yarpRosHelper.h:23
ControlBoardWrapperMotorEncoders::getMotorEncoderAccelerations
bool getMotorEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all motor encoders.
Definition: ControlBoardWrapperMotorEncoders.cpp:285
yarp::dev::impl::jointData::torque
yarp::sig::VectorOf< double > torque
Definition: jointData.h:44
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
yarp::os::Bottle::toString
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:214
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
ControlBoardWrapperLogComponent.h
yarp::sig::VectorOf::resize
void resize(size_t size) override
Resize the vector.
Definition: Vector.h:254
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::os::Bottle::size
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:254
yarp::dev::impl::jointData::pwmDutycycle
yarp::sig::VectorOf< double > pwmDutycycle
Definition: jointData.h:46
yarp::sig
Signal processing.
Definition: Image.h:25
ControlBoardWrapperCommon::timeMutex
std::mutex timeMutex
Definition: ControlBoardWrapperCommon.h:30
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
yarp::dev::VOCAB_JOINTTYPE_REVOLUTE
@ VOCAB_JOINTTYPE_REVOLUTE
Definition: IAxisInfo.h:30
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
MultiJointData::resize
void resize(int _deviceNum, int _maxJointsNumForDevice, WrappedDevice *_device)
Definition: MultiJointData.h:28
yarp::dev::IEncoders
Control board, encoder interface.
Definition: IEncoders.h:121
ControlBoardWrapperInteractionMode::getInteractionModes
bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
Definition: ControlBoardWrapperInteractionMode.cpp:37
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
yarp::dev::PolyDriverList::size
int size() const
Definition: PolyDriverList.cpp:39
yarp::dev::PolyDriver::isValid
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:199
yarp::dev::impl::jointData::motorAcceleration_isValid
bool motorAcceleration_isValid
Definition: jointData.h:43
ROS_enabled
@ ROS_enabled
Definition: yarpRosHelper.h:22
convertDegreesToRadians
double convertDegreesToRadians(double degrees)
convert degrees to radiants for ROS messages
Definition: yarpRosHelper.h:30
yarp::dev::impl::jointData::torque_isValid
bool torque_isValid
Definition: jointData.h:45
ControlBoardWrapper.h
yarp::dev::impl::jointData::motorAcceleration
yarp::sig::VectorOf< double > motorAcceleration
Definition: jointData.h:42
yarp::os::BufferedPort::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: BufferedPort-inl.h:82
yarp::os::Port::removeCallbackLock
bool removeCallbackLock() override
Remove a lock on callbacks added with setCallbackLock()
Definition: Port.cpp:694
yarp::os::Bottle::fromString
void fromString(const std::string &text)
Initializes bottle from a string.
Definition: Bottle.cpp:207
yarp::os::BufferedPort::setEnvelope
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
Definition: BufferedPort-inl.h:232
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
yarp::os::Property::find
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Property.cpp:1034
yarp::os::Port::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:82
yarp::rosmsg::sensor_msgs::JointState::effort
std::vector< yarp::conf::float64_t > effort
Definition: JointState.h:62
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
yarp::os::PortReaderBuffer::attach
void attach(Port &port)
Attach this buffer to a particular port.
Definition: PortReaderBuffer-inl.h:119
yarp::dev::impl::jointData::motorVelocity_isValid
bool motorVelocity_isValid
Definition: jointData.h:41
StreamingMessagesParser::init
void init(yarp::dev::DeviceDriver *x)
Initialization.
Definition: StreamingMessagesParser.cpp:25
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardWrapper::close
bool close() override
Close the device driver by deallocating all resources and closing ports.
Definition: ControlBoardWrapper.cpp:62
yarp::dev::PolyDriver::open
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:143
ControlBoardWrapper::run
void run() override
The thread main loop deals with writing on ports here.
Definition: ControlBoardWrapper.cpp:777
yarp::dev::DeviceResponder::attach
void attach(yarp::os::TypedReader< yarp::os::Bottle > &source)
Attach this object to a source of messages.
Definition: DeviceDriver.h:202
yarp::os::PeriodicThread::isRunning
bool isRunning() const
Returns true when the thread is started, false otherwise.
Definition: PeriodicThread.cpp:316
yarp::os::Bottle::find
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:290
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
yarp::dev::impl::jointData::jointVelocity
yarp::sig::VectorOf< double > jointVelocity
Definition: jointData.h:34
yarp::dev::impl::jointData
Definition: jointData.h:29
yarp::os::Port::setEnvelope
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
Definition: Port.cpp:541
ControlBoardWrapperMotorEncoders::getMotorEncoderSpeeds
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all motor encoders.
Definition: ControlBoardWrapperMotorEncoders.cpp:240
yarp::os::BufferedPort::prepare
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
Definition: BufferedPort-inl.h:114
yarp::sig::VectorOf< double >
yarp::os::Bottle::check
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:280
yarp::dev::impl::jointData::motorVelocity
yarp::sig::VectorOf< double > motorVelocity
Definition: jointData.h:40
yarp::os::Bottle::findGroup
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
Definition: Bottle.cpp:305
ControlBoardWrapperAxisInfo::getJointType
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
Definition: ControlBoardWrapperAxisInfo.cpp:36
yarp::rosmsg::std_msgs::Header::seq
std::uint32_t seq
Definition: Header.h:47
ControlBoardWrapperMotorEncoders::getMotorEncoders
bool getMotorEncoders(double *encs) override
Read the position of all motor encoders.
Definition: ControlBoardWrapperMotorEncoders.cpp:146
yarp::os::Publisher::topic
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:67
yarp::rosmsg::sensor_msgs::JointState::velocity
std::vector< yarp::conf::float64_t > velocity
Definition: JointState.h:61
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
yarp::os::Publisher::write
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:152
yarp::os::Property::toString
std::string toString() const override
Return a standard text representation of the content of the object.
Definition: Property.cpp:1052
CONTROLBOARDWRAPPER
const yarp::os::LogComponent & CONTROLBOARDWRAPPER()
Definition: ControlBoardWrapperLogComponent.cpp:11
ControlBoardWrapperCommon::partName
std::string partName
Definition: ControlBoardWrapperCommon.h:24
yarp::dev::impl::jointData::jointPosition_isValid
bool jointPosition_isValid
Definition: jointData.h:33
yarp::os::Stamp::getTime
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:37
ControlBoardWrapperCommon::controlledJoints
size_t controlledJoints
Definition: ControlBoardWrapperCommon.h:23
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
yarp::dev::impl::jointData::pwmDutycycle_isValid
bool pwmDutycycle_isValid
Definition: jointData.h:47
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
WrappedDevice::getSubdevice
SubDevice * getSubdevice(size_t i)
Definition: SubDevice.h:129
yarp::dev::PolyDriver::close
bool close() override
Close the DeviceDriver.
Definition: PolyDriver.cpp:176
ROS_disabled
@ ROS_disabled
Definition: yarpRosHelper.h:21
yarp::dev::InteractionModeEnum
InteractionModeEnum
Definition: IInteractionMode.h:21
yarp::os::BufferedPort::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: BufferedPort-inl.h:41
WrappedDevice::subdevices
SubDeviceVector subdevices
Definition: SubDevice.h:125
ControlBoardWrapperPWMControl::getDutyCycles
bool getDutyCycles(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
Definition: ControlBoardWrapperPWMControl.cpp:128
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
ControlBoardWrapperEncodersTimed::getEncoderSpeeds
bool getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
Definition: ControlBoardWrapperEncodersTimed.cpp:234
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
ControlBoardWrapper::~ControlBoardWrapper
~ControlBoardWrapper() override
yarp::rosmsg::sensor_msgs::JointState::header
yarp::rosmsg::std_msgs::Header header
Definition: JointState.h:58
yarp::os::Node
The Node class.
Definition: Node.h:27
yarp::os::Property::check
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Property.cpp:1024
yarp::sig::VectorOf::end
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
Definition: Vector.h:490
yarp::dev::impl::jointData::motorPosition_isValid
bool motorPosition_isValid
Definition: jointData.h:39
ControlBoardWrapperEncodersTimed::getEncoderAccelerations
bool getEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all axes.
Definition: ControlBoardWrapperEncodersTimed.cpp:285
ControlBoardWrapperTorqueControl::getTorques
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
Definition: ControlBoardWrapperTorqueControl.cpp:203
yarp::dev::impl::jointData::motorPosition
yarp::sig::VectorOf< double > motorPosition
Definition: jointData.h:38
yarp::dev::impl::jointData::jointAcceleration
yarp::sig::VectorOf< double > jointAcceleration
Definition: jointData.h:36
yarp::os::Port::setReader
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:505
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
ControlBoardWrapper::ControlBoardWrapper
ControlBoardWrapper()
Definition: ControlBoardWrapper.cpp:33
yarp::dev::impl::jointData::jointPosition
yarp::sig::VectorOf< double > jointPosition
Definition: jointData.h:32
LogComponent.h
yarp::dev::impl::jointData::interactionMode
yarp::sig::VectorOf< int > interactionMode
Definition: jointData.h:52
ControlBoardWrapper::detachAll
bool detachAll() override
Detach the object (you must have first called attach).
Definition: ControlBoardWrapper.cpp:753
ControlBoardWrapper::attachAll
bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
Definition: ControlBoardWrapper.cpp:694
yarp::os::Bottle::isNull
bool isNull() const override
Checks if the object is invalid.
Definition: Bottle.cpp:373
ControlBoardWrapperCommon::device
WrappedDevice device
Definition: ControlBoardWrapperCommon.h:22
yarp::os::PortWriterBuffer::attach
void attach(Port &port)
Set the Port to which objects will be written.
Definition: PortWriterBuffer.h:125
yarp::dev::impl::jointData::jointAcceleration_isValid
bool jointAcceleration_isValid
Definition: jointData.h:37
yarp::dev::IEncoders::getAxes
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
yarp::os::Bottle::tail
Bottle tail() const
Get all but the first element of a bottle.
Definition: Bottle.cpp:391
yarp::sig::VectorOf::data
T * data()
Return a pointer to the first element of the vector.
Definition: Vector.h:239
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::os::Value::asInt32
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
yarp::dev::impl::jointData::current
yarp::sig::VectorOf< double > current
Definition: jointData.h:48
jointData.h
yarp::os::Stamp::update
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:113
yarp::os::BufferedPort::write
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
Definition: BufferedPort-inl.h:126
yarp::dev::impl
Definition: jointData.cpp:18
MultiJointData::destroy
void destroy()
Definition: MultiJointData.h:53
ControlBoardWrapperCommon::getCurrents
bool getCurrents(double *currs)
Definition: ControlBoardWrapperCommon.cpp:296
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
WrappedDevice::lut
std::vector< DevicesLutEntry > lut
Definition: SubDevice.h:126
SubDevice::detach
void detach()
Definition: SubDevice.cpp:63
ControlBoardWrapperControlMode::getControlModes
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
Definition: ControlBoardWrapperControlMode.cpp:37
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
RPCMessagesParser::init
void init(yarp::dev::DeviceDriver *x)
Initialization.
Definition: RPCMessagesParser.cpp:2365
SubDevice::totalAxis
size_t totalAxis
Definition: SubDevice.h:63
yarp::rosmsg::sensor_msgs::JointState::name
std::vector< std::string > name
Definition: JointState.h:59
yarp::os::PortWriterBuffer::get
T & get()
A synonym of PortWriterBuffer::prepare.
Definition: PortWriterBuffer.h:102
yarp::os::PortWriterBuffer::write
void write(bool forceStrict=false)
Try to write the last buffer returned by PortWriterBuffer::get.
Definition: PortWriterBuffer.h:133
yarp::os::BufferedPort::close
void close() override
Stop port activity.
Definition: BufferedPort-inl.h:73
yarp::dev::impl::jointData::controlMode_isValid
bool controlMode_isValid
Definition: jointData.h:51
yarp::os::Port::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:377
yarp::os::Value::asList
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:243
yarp::os::PeriodicThread::stop
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
Definition: PeriodicThread.cpp:296
yarp::os::Property::findGroup
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
Definition: Property.cpp:1125
RPCMessagesParser::initialize
virtual bool initialize()
Initialize the internal data.
Definition: RPCMessagesParser.cpp:2325
RPCMessagesParser.h
yarp::os::Value::toString
std::string toString() const override
Return a standard text representation of the content of the object.
Definition: Value.cpp:359
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
SubDevice
Definition: SubDevice.h:55
yarp::rosmsg::sensor_msgs::JointState::position
std::vector< yarp::conf::float64_t > position
Definition: JointState.h:60
ROS_config_error
@ ROS_config_error
Definition: yarpRosHelper.h:20
WrappedDevice::maxNumOfJointsInDevices
size_t maxNumOfJointsInDevices
Definition: SubDevice.h:127
yarp::sig::VectorOf::begin
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
Definition: Vector.h:483
yarp::dev::IRemoteCalibrator
IRemoteCalibrator interface is meant to remotize the access of the calibration device in order to all...
Definition: IRemoteCalibrator.h:30
yarp::os::Property::unput
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1029
yarp::dev::JointTypeEnum
JointTypeEnum
Definition: IAxisInfo.h:29
ControlBoardWrapper::open
bool open(yarp::os::Searchable &prop) override
Open the device driver.
Definition: ControlBoardWrapper.cpp:338
yarp::rosmsg::std_msgs::Header::stamp
yarp::rosmsg::TickTime stamp
Definition: Header.h:48
ControlBoardWrapperEncodersTimed::getEncodersTimed
bool getEncodersTimed(double *encs, double *t) override
Read the instantaneous acceleration of all axes.
Definition: ControlBoardWrapperEncodersTimed.cpp:156
yarp::dev::impl::jointData::jointVelocity_isValid
bool jointVelocity_isValid
Definition: jointData.h:35
yarp::dev::impl::jointData::interactionMode_isValid
bool interactionMode_isValid
Definition: jointData.h:53
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
StreamingMessagesParser::initialize
bool initialize()
Definition: StreamingMessagesParser.cpp:37
SubDevice::configure
bool configure(size_t wbase, size_t wtop, size_t base, size_t top, size_t axes, const std::string &id, ControlBoardWrapper *_parent)
Definition: SubDevice.cpp:27
StreamingMessagesParser.h
yarp::os::Value::isInt32
virtual bool isInt32() const
Checks if value is a 32-bit integer.
Definition: Value.cpp:135