YARP
Yet Another Robot Platform
AnalogWrapper.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #include "AnalogWrapper.h"
7 #include <sstream>
8 #include <iostream>
10 #include <yarp/os/LogComponent.h>
11 #include <yarp/os/LogStream.h>
12 
13 using namespace yarp::sig;
14 using namespace yarp::dev;
15 using namespace yarp::os;
16 
17 
18 YARP_LOG_COMPONENT(ANALOGWRAPPER, "yarp.devices.AnalogWrapper")
19 
20 
25  public yarp::os::PortReader
26 {
27  yarp::dev::IAnalogSensor* is; // analog sensor to calibrate, when required
28  yarp::os::Port rpcPort; // rpc port related to the analog sensor
29 
30 public:
31  AnalogServerHandler(const char* n);
33 
34  void setInterface(yarp::dev::IAnalogSensor *is);
35 
36  bool _handleIAnalog(yarp::os::Bottle &cmd, yarp::os::Bottle &reply);
37 
38  bool read(yarp::os::ConnectionReader& connection) override;
39 };
40 
41 
48 {
49 public:
51  std::string port_name; // the complete name of the port
52  int offset; // an offset, the port is mapped starting from this taxel
53  int length; // length of the output vector of the port (-1 for max length)
55  AnalogPortEntry(const AnalogPortEntry &alt);
56  AnalogPortEntry &operator =(const AnalogPortEntry &alt);
57 };
58 
59 
65 AnalogServerHandler::AnalogServerHandler(const char* n) : is(nullptr)
66 {
67  rpcPort.open(n);
68  rpcPort.setReader(*this);
69 }
70 
72 {
73  rpcPort.close();
74  is = nullptr;
75 }
76 
78 {
79  this->is = is;
80 }
81 
83 {
84  if (is == nullptr) {
85  return false;
86  }
87 
88  const size_t msgsize=cmd.size();
89  int ret=IAnalogSensor::AS_ERROR;
90 
91  int code=cmd.get(1).asVocab32();
92  switch (code)
93  {
94  case VOCAB_CALIBRATE:
95  if (msgsize == 2) {
96  ret = is->calibrateSensor();
97  } else if (msgsize > 2) {
98  size_t offset = 2;
99  Vector v(msgsize - offset);
100  for (unsigned int i = 0; i < v.size(); i++) {
101  v[i] = cmd.get(i + offset).asFloat64();
102  }
103  ret = is->calibrateSensor(v);
104  }
105  break;
107  if (msgsize==3)
108  {
109  int ch=cmd.get(2).asInt32();
110  ret=is->calibrateChannel(ch);
111  }
112  else if (msgsize==4)
113  {
114  int ch=cmd.get(2).asInt32();
115  double v=cmd.get(3).asFloat64();
116  ret=is->calibrateChannel(ch, v);
117  }
118  break;
119  default:
120  return false;
121  }
122 
123  reply.addInt32(ret);
124  return true;
125 }
126 
128 {
129  yarp::os::Bottle in;
130  yarp::os::Bottle out;
131  bool ok=in.read(connection);
132  if (!ok) {
133  return false;
134  }
135 
136  // parse in, prepare out
137  int code = in.get(0).asVocab32();
138  bool ret=false;
139  if (code==VOCAB_IANALOG)
140  {
141  ret=_handleIAnalog(in, out);
142  }
143 
144  if (!ret)
145  {
146  out.clear();
148  }
149 
150  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
151  if (returnToSender!=nullptr) {
152  out.write(*returnToSender);
153  }
154  return true;
155 }
156 
157 
165  offset(0),
166  length(0)
167 {}
168 
170 {
171  this->length = alt.length;
172  this->offset = alt.offset;
173  this->port_name = alt.port_name;
174 }
175 
177 {
178  this->length = alt.length;
179  this->offset = alt.offset;
180  this->port_name = alt.port_name;
181  return *this;
182 }
183 
184  // closing anonimous namespace
185 
186 
192 bool AnalogWrapper::createPort(const char* name, int rate)
193 {
194  analogSensor_p=nullptr;
195  analogPorts.resize(1);
196  analogPorts[0].offset = 0;
197  analogPorts[0].length = -1; // max length
198  analogPorts[0].port_name = std::string(name);
199  setHandlers();
200  setPeriod(rate / 1000.0);
201  return true;
202 }
203 
204 bool AnalogWrapper::createPorts(const std::vector<AnalogPortEntry>& _analogPorts, int rate)
205 {
206  analogSensor_p=nullptr;
207  this->analogPorts=_analogPorts;
208  setHandlers();
209  setPeriod(rate / 1000.0);
210  return true;
211 }
212 
215 {
216  // init ROS struct
217  frame_idVec.resize(1);
218  frame_idVec.at(0) = "";
219  rosTopicNamesVec.resize(1);
220  rosTopicNamesVec.at(0) = "";
221  rosMsgCounterVec.resize(1);
222  rosMsgCounterVec.at(0) = 0;
223 }
224 
226 {
227  threadRelease();
228  close();
229  _rate = DEFAULT_THREAD_PERIOD;
230  analogSensor_p = nullptr;
231 }
232 
233 void AnalogWrapper::setHandlers()
234 {
235  for(auto& analogPort : analogPorts)
236  {
237  std::string rpcPortName = analogPort.port_name;
238  rpcPortName += "/rpc:i";
239  auto* ash = new AnalogServerHandler(rpcPortName.c_str());
240  handlers.push_back(ash);
241  }
242 }
243 
244 void AnalogWrapper::removeHandlers()
245 {
246  for(auto& handler : handlers)
247  {
248  if (handler != nullptr)
249  {
250  delete handler;
251  handler = nullptr;
252  }
253  }
254  handlers.clear();
255 }
256 
257 bool AnalogWrapper::openAndAttachSubDevice(Searchable &prop)
258 {
259  Property p;
260  subDeviceOwned = new PolyDriver;
261  p.fromString(prop.toString());
262 
263 // p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
264  p.unput("device");
265  p.put("device", prop.find("subdevice").asString()); // subdevice was already checked before
266 
267  // if errors occurred during open, quit here.
268  yCDebug(ANALOGWRAPPER, "opening AnalogWrapper subdevice...");
269  subDeviceOwned->open(p);
270 
271  if (!subDeviceOwned->isValid())
272  {
273  yCError(ANALOGWRAPPER, "opening AnalogWrapper subdevice... FAILED\n");
274  return false;
275  }
276 
277  subDeviceOwned->view(analogSensor_p);
278 
279  if (analogSensor_p == nullptr)
280  {
281  yCError(ANALOGWRAPPER, "Opening IAnalogSensor interface of AnalogWrapper subdevice... FAILED\n");
282  return false;
283  }
284 
285  int chNum = analogSensor_p->getChannels();
286 
287  if (chNum <= 0)
288  {
289  yCError(ANALOGWRAPPER, "Calling analog sensor has invalid channels number %d.\n", chNum);
290  return false;
291  }
292 
293  attach(analogSensor_p);
294  PeriodicThread::setPeriod(_rate / 1000.0);
295  return PeriodicThread::start();
296 }
297 
298 
299 bool AnalogWrapper::openDeferredAttach(yarp::os::Searchable &prop)
300 {
301  // nothing to do here?
302  if ((subDeviceOwned != nullptr) || (ownDevices == true)) {
303  yCError(ANALOGWRAPPER) << "AnalogWrapper: something wrong with the initialization.";
304  }
305  return true;
306 }
307 
308 
313 bool AnalogWrapper::attachAll(const PolyDriverList &analog2attach)
314 {
315  //check if we already instantiated a subdevice previously
316  if (ownDevices) {
317  return false;
318  }
319 
320  if (analog2attach.size() != 1)
321  {
322  yCError(ANALOGWRAPPER, "AnalogWrapper: cannot attach more than one device");
323  return false;
324  }
325 
326  yarp::dev::PolyDriver * Idevice2attach=analog2attach[0]->poly;
327 
328  if (Idevice2attach->isValid())
329  {
330  Idevice2attach->view(analogSensor_p);
331  }
332 
333  if(nullptr == analogSensor_p)
334  {
335  yCError(ANALOGWRAPPER, "AnalogWrapper: subdevice passed to attach method is invalid");
336  return false;
337  }
338  attach(analogSensor_p);
339  PeriodicThread::setPeriod(_rate / 1000.0);
340  return PeriodicThread::start();
341 }
342 
344 {
345  //check if we already instantiated a subdevice previously
346  if (ownDevices) {
347  return false;
348  }
349 
350  analogSensor_p = nullptr;
351  for(unsigned int i=0; i<analogPorts.size(); i++)
352  {
353  if (handlers[i] != nullptr) {
354  handlers[i]->setInterface(analogSensor_p);
355  }
356  }
357  return true;
358 }
359 
361 {
362  analogSensor_p=s;
363  for(unsigned int i=0; i<analogPorts.size(); i++)
364  {
365  handlers[i]->setInterface(analogSensor_p);
366  }
367  //Resize vector of read data to avoid further allocation of memory
368  //as long as the number of channels does not change
369  lastDataRead.resize((size_t)analogSensor_p->getChannels(),0.0);
370 }
371 
373 {
374  // Set interface to NULL
375  analogSensor_p = nullptr;
376  for(unsigned int i=0; i<analogPorts.size(); i++)
377  {
378  handlers[i]->setInterface(analogSensor_p);
379  }
380 }
381 
383 {
384  for(auto& analogPort : analogPorts)
385  {
386  // open data port
387  if (!analogPort.port.open(analogPort.port_name))
388  {
389  yCError(ANALOGWRAPPER, "AnalogWrapper: failed to open port %s", analogPort.port_name.c_str());
390  return false;
391  }
392  }
393  return true;
394 }
395 
396 void AnalogWrapper::setId(const std::string &id)
397 {
398  sensorId=id;
399 }
400 
401 std::string AnalogWrapper::getId()
402 {
403  return sensorId;
404 }
405 
406 bool AnalogWrapper::checkROSParams(Searchable &config)
407 {
408  // check for ROS parameter group
409  if(!config.check("ROS") )
410  {
411  useROS = ROS_disabled;
412  yCInfo(ANALOGWRAPPER) << "No ROS group found in config file ... skipping ROS initialization.";
413  return true;
414  }
415 
416  yCInfo(ANALOGWRAPPER) << "ROS group was FOUND in config file.";
417 
418  Bottle &rosGroup = config.findGroup("ROS");
419  if(rosGroup.isNull())
420  {
421  yCError(ANALOGWRAPPER) << sensorId << "ROS group params is not a valid group or empty";
422  useROS = ROS_config_error;
423  return false;
424  }
425 
426  // check for useROS parameter
427  if(!rosGroup.check("useROS"))
428  {
429  yCError(ANALOGWRAPPER) << sensorId << " cannot find useROS parameter, mandatory when using ROS message. \n \
430  Allowed values are true, false, ROS_only";
431  useROS = ROS_config_error;
432  return false;
433  }
434  std::string ros_use_type = rosGroup.find("useROS").asString();
435  if(ros_use_type == "false")
436  {
437  yCInfo(ANALOGWRAPPER) << sensorId << "useROS topic if set to 'false'";
438  useROS = ROS_disabled;
439  return true;
440  }
441  else if(ros_use_type == "true")
442  {
443  yCInfo(ANALOGWRAPPER) << sensorId << "useROS topic if set to 'true'";
444  useROS = ROS_enabled;
445  }
446  else if(ros_use_type == "only")
447  {
448  yCInfo(ANALOGWRAPPER) << sensorId << "useROS topic if set to 'only";
449  useROS = ROS_only;
450  }
451  else
452  {
453  yCInfo(ANALOGWRAPPER) << sensorId << "useROS parameter is set to unvalid value ('" << ros_use_type << "'), supported values are 'true', 'false', 'only'";
454  useROS = ROS_config_error;
455  return false;
456  }
457 
458  // check for ROS_nodeName parameter
459  if(!rosGroup.check("ROS_nodeName"))
460  {
461  yCError(ANALOGWRAPPER) << sensorId << " cannot find ROS_nodeName parameter, mandatory when using ROS message";
462  useROS = ROS_config_error;
463  return false;
464  }
465  rosNodeName = rosGroup.find("ROS_nodeName").asString(); // TODO: check name is correct
466  yCInfo(ANALOGWRAPPER) << sensorId << "rosNodeName is " << rosNodeName;
467 
468  // check for ROS_topicName parameter
469  if(!rosGroup.check("ROS_topicName"))
470  {
471  yCError(ANALOGWRAPPER) << sensorId << " cannot find ROS_topicName parameter, mandatory when using ROS message";
472  useROS = ROS_config_error;
473  return false;
474  }
475 
476  if(rosGroup.find("ROS_topicName").isString())
477  {
478  rosTopicNamesVec.at(0) = rosGroup.find("ROS_topicName").asString();
479  yCInfo(ANALOGWRAPPER) << sensorId << "ROS_topicName is " << rosTopicNamesVec.at(0);
480 
481  }
482  else if(rosGroup.find("ROS_topicName").isList())
483  {
484  yarp::os::Bottle *rosTopicNamesBottle = rosGroup.find("ROS_topicName").asList();
485  yCInfo(ANALOGWRAPPER) << sensorId << "ROS_topicName list is " << rosTopicNamesBottle->toString();
486 
487  rosTopicNamesVec.resize(rosTopicNamesBottle->size());
488  for(size_t i = 0; i < rosTopicNamesBottle->size(); i++)
489  {
490  rosTopicNamesVec.at(i) = rosTopicNamesBottle->get(i).asString();
491  }
492 
493  // resize the ros msg counter vector
494  rosMsgCounterVec.resize(rosTopicNamesVec.size());
495  }
496 
497  // check for ROS_msgType parameter
498  if (!rosGroup.check("ROS_msgType"))
499  {
500  yCError(ANALOGWRAPPER) << sensorId << " cannot find ROS_msgType parameter, mandatory when using ROS message";
501  useROS = ROS_config_error;
502  return false;
503  }
504  rosMsgType = rosGroup.find("ROS_msgType").asString();
505 
506  // check for frame_id parameter
507  if (rosMsgType == "geometry_msgs/WrenchStamped")
508  {
509  yCInfo(ANALOGWRAPPER) << sensorId << "ROS_msgType is " << rosMsgType;
510  if (!rosGroup.check("frame_id"))
511  {
512  yCError(ANALOGWRAPPER) << sensorId << " cannot find frame_id parameter, mandatory when using ROS message";
513  useROS = ROS_config_error;
514  return false;
515  }
516 
517  if(rosGroup.find("frame_id").isString())
518  {
519  frame_idVec.at(0) = rosGroup.find("frame_id").asString();
520  yCInfo(ANALOGWRAPPER) << sensorId << "frame_id is " << frame_idVec.at(0);
521 
522  }
523  else if(rosGroup.find("frame_id").isList())
524  {
525  yarp::os::Bottle *frame_idBottle = rosGroup.find("frame_id").asList();
526 
527  if(frame_idBottle->size() != rosTopicNamesVec.size())
528  {
529  yCError(ANALOGWRAPPER, "AnalogWrapper: mismatch between the number of ros topics and frame_ids");
530  return false;
531  }
532 
533  yCInfo(ANALOGWRAPPER) << sensorId << "frame_id list is " << frame_idBottle->toString();
534 
535  frame_idVec.resize(frame_idBottle->size());
536  for(size_t i = 0; i < frame_idBottle->size(); i++)
537  {
538  frame_idVec.at(i) = frame_idBottle->get(i).asString();
539  }
540  }
541 
542  if(!rosGroup.check("rosOffset"))
543  {
544  yCWarning(ANALOGWRAPPER) << sensorId << "cannot find rosOffset parameter, using the default offset 0 while reading analog sensor data";
545  }
546 
547  if(rosGroup.find("rosOffset").isInt32())
548  {
549  rosOffset = rosGroup.find("rosOffset").asInt32();
550  yCInfo(ANALOGWRAPPER) << sensorId << " rosOffset is " << rosOffset;
551  }
552 
553  if(!rosGroup.check("rosPadding"))
554  {
555  yCWarning(ANALOGWRAPPER) << sensorId << "cannot find rosPadding parameter, using the default padding 0 while reading analog sensor data";
556  }
557 
558  if(rosGroup.find("rosPadding").isInt32())
559  {
560  rosOffset = rosGroup.find("rosPadding").asInt32();
561  yCInfo(ANALOGWRAPPER) << sensorId << " rosPadding is " << rosOffset;
562  }
563  }
564  else if (rosMsgType == "sensor_msgs/JointState")
565  {
566  std::string jointName;
567  yCInfo(ANALOGWRAPPER) << sensorId << "ROS_msgType is " << rosMsgType;
568  bool oldParam = false;
569  bool newParam = false;
570 
571  if(rosGroup.check("joint_names"))
572  {
573  oldParam = true;
574  jointName = "joint_names";
575  yCWarning(ANALOGWRAPPER) << sensorId << " using DEPRECATED 'joint_names' parameter. Please use 'jointNames' instead.";
576  }
577 
578  if(rosGroup.check("jointNames"))
579  {
580  newParam = true;
581  jointName = "jointNames";
582  }
583 
584  if(!oldParam && !newParam)
585  {
586  yCError(ANALOGWRAPPER) << sensorId << " missing 'jointNames' parameter needed when broadcasting 'sensor_msgs/JointState' message type";
587  useROS = ROS_config_error;
588  return false;
589  }
590  // Throw an error if both new and old are present
591  if(oldParam && newParam)
592  {
593  yCError(ANALOGWRAPPER) << sensorId << " found both DEPRECATED 'joint_names' and new 'jointNames' parameters. Please remove the old 'joint_names' from your config file.";
594  useROS = ROS_config_error;
595  return false;
596  }
597 
598  yarp::os::Bottle& jnam = rosGroup.findGroup(jointName);
599  if(jnam.isNull())
600  {
601  yCError(ANALOGWRAPPER) << sensorId << "Cannot find 'jointNames' parameters.";
602  return false;
603  }
604 
605  // Cannot check number of channels here because need to wait for the attach function
606  int joint_names_size = jnam.size()-1;
607  for (int i = 0; i < joint_names_size; i++)
608  {
609  ros_joint_names.push_back(jnam.get(i+1).asString());
610  }
611  }
612  else
613  {
614  yCError(ANALOGWRAPPER) << sensorId << "ROS_msgType '" << rosMsgType << "' not supported ";
615  return false;
616  }
617 
618  return true;
619 }
620 
621 bool AnalogWrapper::initialize_ROS()
622 {
623  bool success = false;
624  switch(useROS)
625  {
626  case ROS_enabled:
627  case ROS_only:
628  {
629  rosNode = new yarp::os::Node(rosNodeName); // add a ROS node
630 
631  if(rosNode == nullptr)
632  {
633  yCError(ANALOGWRAPPER) << " opening " << rosNodeName << " Node, check your yarp-ROS network configuration\n";
634  success = false;
635  break;
636  }
637 
638  if (rosMsgType == "geometry_msgs/WrenchStamped")
639  {
640  rosPublisherWrenchPortVec.resize(rosTopicNamesVec.size());
641 
642  for(size_t i = 0; i < rosTopicNamesVec.size(); i++)
643  {
644  if(!rosPublisherWrenchPortVec.at(i).topic(rosTopicNamesVec.at(i)))
645  {
646  yCError(ANALOGWRAPPER) << " opening " << rosTopicNamesVec.at(i) << " Topic, check your yarp-ROS network configuration\n";
647  success = false;
648  break;
649  }
650  }
651  }
652  else if (rosMsgType == "sensor_msgs/JointState")
653  {
654  if (!rosPublisherJointPort.topic(rosTopicNamesVec.at(0)))
655  {
656  yCError(ANALOGWRAPPER) << " opening " << rosTopicNamesVec.at(0) << " Topic, check your yarp-ROS network configuration\n";
657  success = false;
658  break;
659  }
660  }
661  else
662  {
663  yCError(ANALOGWRAPPER) << sensorId << "Invalid rosMsgType: " << rosMsgType;
664  }
665 
666  yCInfo(ANALOGWRAPPER) << sensorId << "ROS initialized successfully, node:" << rosNodeName << " and opened the following topics: ";
667  for(size_t i = 0; i < rosTopicNamesVec.size(); i++)
668  {
669  yCInfo(ANALOGWRAPPER) << rosTopicNamesVec.at(0);
670  }
671 
672  success = true;
673  } break;
674 
675  case ROS_disabled:
676  {
677  yCInfo(ANALOGWRAPPER) << sensorId << ": no ROS initialization required";
678  success = true;
679  } break;
680 
681  case ROS_config_error:
682  {
683  yCError(ANALOGWRAPPER) << sensorId << " ROS parameter are not correct, check your configuration file";
684  success = false;
685  } break;
686 
687  default:
688  {
689  yCError(ANALOGWRAPPER) << sensorId << " something went wrong with ROS configuration, we should never be here!!!";
690  success = false;
691  } break;
692  }
693  return success;
694 }
695 
697 {
698  yCWarning(ANALOGWRAPPER) << "The 'AnalogWrapper' device is deprecated.";
699  yCWarning(ANALOGWRAPPER) << "Possible alternatives, depending on the specific type sensor data, are:";
700  yCWarning(ANALOGWRAPPER) << "'MultipleAnalogSensorsRemapper`+`MultipleAnalogSensorsServer`, `PoseStampedRosPublisher`, `WrenchStampedRosPublisher`,`IMURosPublisher`,etc.";
701  yCWarning(ANALOGWRAPPER) << "The old device is no longer supported, and it will be deprecated in YARP 3.6 and removed in YARP 4.";
702  yCWarning(ANALOGWRAPPER) << "Please update your scripts.";
703 
704  Property params;
705  params.fromString(config.toString());
706  yCTrace(ANALOGWRAPPER) << "AnalogWrapper params are: " << config.toString();
707 
708  if (!config.check("period"))
709  {
710  yCError(ANALOGWRAPPER) << "AnalogWrapper: missing 'period' parameter. Check you configuration file\n";
711  return false;
712  }
713  else
714  {
715  _rate = config.find("period").asInt32();
716  }
717 
718  if (config.check("deviceId"))
719  {
720  yCError(ANALOGWRAPPER) << "AnalogWrapper: the parameter 'deviceId' has been removed, please use parameter 'name' instead. \n"
721  << "e.g. In the FT wrapper configuration files of your robot, replace '<param name=""deviceId""> left_arm </param>' \n"
722  << "with '/icub/left_arm/analog:o' ";
723  return false;
724  }
725 
726  if (!config.check("name"))
727  {
728  yCError(ANALOGWRAPPER) << "AnalogWrapper: missing 'name' parameter. Check you configuration file; it must be like:\n"
729  " name: full name of the port, like /robotName/deviceId/sensorType:o";
730  return false;
731  }
732  else
733  {
734  streamingPortName = config.find("name").asString();
735  setId("AnalogServer");
736  }
737 
738  if(!checkROSParams(config) )
739  {
740  yCError(ANALOGWRAPPER) << sensorId << "ROS parameter are not correct, check your configuration file";
741  return false;
742  }
743 
744  if(!initialize_YARP(config) )
745  {
746  yCError(ANALOGWRAPPER) << sensorId << "Error initializing YARP ports";
747  return false;
748  }
749 
750  if(!initialize_ROS() )
751  {
752  yCError(ANALOGWRAPPER) << sensorId << "Error initializing ROS topics";
753  return false;
754  }
755 
756  // check if we need to create subdevice or if they are
757  // passed later on thorugh attachAll()
758  if(config.check("subdevice"))
759  {
760  ownDevices=true;
761  if(! openAndAttachSubDevice(config))
762  {
763  yCError(ANALOGWRAPPER, "AnalogWrapper: error while opening subdevice\n");
764  return false;
765  }
766  }
767  else
768  {
769  ownDevices=false;
770  if (!openDeferredAttach(config)) {
771  return false;
772  }
773  }
774 
775  return true;
776 }
777 
778 bool AnalogWrapper::initialize_YARP(yarp::os::Searchable &params)
779 {
780  switch(useROS)
781  {
782  case ROS_only:
783  {
784  yCInfo(ANALOGWRAPPER) << sensorId << " No YARP initialization required";
785  return true;
786  } break;
787 
788  default:
789  {
790  // Create the list of ports
791  // port names are optional, do not check for correctness.
792  if(!params.check("ports"))
793  {
794  // if there is no "ports" section open only 1 port and use name as is.
795  if (Network::exists(streamingPortName + "/rpc:i") || Network::exists(streamingPortName))
796  {
797  yCError(ANALOGWRAPPER) << "AnalogWrapper: unable to open the analog server, address conflict";
798  return false;
799  }
800  createPort((streamingPortName ).c_str(), _rate );
801  // since createPort always return true, check the port is really been opened is done here
802  if (!Network::exists(streamingPortName + "/rpc:i")) {
803  return false;
804  }
805  }
806  else
807  {
808  Bottle *ports=params.find("ports").asList();
809 
810  Value &deviceChannels = params.find("channels");
811  if (deviceChannels.isNull())
812  {
813  yCError(ANALOGWRAPPER, "AnalogWrapper: 'channels' parameters was not found in config file.");
814  return false;
815  }
816 
817  int nports=ports->size();
818  int sumOfChannels = 0;
819  std::vector<AnalogPortEntry> tmpPorts;
820  tmpPorts.resize(nports);
821 
822  for(size_t k=0; k<ports->size(); k++)
823  {
824  Bottle parameters=params.findGroup(ports->get(k).asString());
825 
826  if (parameters.size()!=5)
827  {
828  yCError(ANALOGWRAPPER) << "AnalogWrapper: check skin port parameters in part description, I was expecting "
829  << ports->get(k).asString().c_str() << " followed by four integers";
830  yCError(ANALOGWRAPPER) << " your param is " << parameters.toString();
831  return false;
832  }
833 
834  if (Network::exists(streamingPortName + "/" + std::string(ports->get(k).asString()) + "/rpc:i")
835  || Network::exists(streamingPortName + "/" + std::string(ports->get(k).asString())))
836  {
837  yCError(ANALOGWRAPPER) << "AnalogWrapper: unable to open the analog server, address conflict";
838  return false;
839  }
840  int wBase=parameters.get(1).asInt32();
841  int wTop=parameters.get(2).asInt32();
842  int base=parameters.get(3).asInt32();
843  int top=parameters.get(4).asInt32();
844 
845  yCDebug(ANALOGWRAPPER) << "--> " << wBase << " " << wTop << " " << base << " " << top;
846 
847  //check consistenty
848  if(wTop-wBase != top-base){
849  yCError(ANALOGWRAPPER) << "AnalogWrapper: numbers of mapped taxels do not match, check "
850  << ports->get(k).asString().c_str() << " port parameters in part description";
851  return false;
852  }
853  int portChannels = top-base+1;
854 
855  tmpPorts[k].length = portChannels;
856  tmpPorts[k].offset = wBase;
857  yCDebug(ANALOGWRAPPER) << "opening port " << ports->get(k).asString().c_str();
858  tmpPorts[k].port_name = streamingPortName+ "/" + std::string(ports->get(k).asString());
859 
860  sumOfChannels+=portChannels;
861  }
862  createPorts(tmpPorts, _rate);
863 
864  if (sumOfChannels!=deviceChannels.asInt32())
865  {
866  yCError(ANALOGWRAPPER) << "AnalogWrapper: Total number of mapped taxels does not correspond to total taxels";
867  return false;
868  }
869  }
870  } break;
871  }
872  return true;
873 }
874 
876 {
877  for(auto& analogPort : analogPorts)
878  {
879  analogPort.port.interrupt();
880  analogPort.port.close();
881  }
882 }
883 
885 {
886  int first, last, ret;
887 
888  if (analogSensor_p!=nullptr)
889  {
890  ret=analogSensor_p->read(lastDataRead);
891 
893  {
894  if (lastDataRead.size()>0)
895  {
896  if(useROS != ROS_only)
897  {
898  lastStateStamp.update();
899  // send the data on the port(s), splitting them as specified in the config file
900  for(auto& analogPort : analogPorts)
901  {
902  yarp::sig::Vector &pv = analogPort.port.prepare();
903  first = analogPort.offset;
904  if (analogPort.length == -1) { // read the max length available
905  last = lastDataRead.size()-1;
906  } else {
907  last = analogPort.offset + analogPort.length - 1;
908  }
909 
910  // check vector limit
911  if(last>=(int)lastDataRead.size()){
912  yCError(ANALOGWRAPPER, )<<"AnalogWrapper: error while sending analog sensor output on port "<< analogPort.port_name
913  <<" Vector size expected to be at least "<<last<<" whereas it is "<< lastDataRead.size();
914  continue;
915  }
916  pv = lastDataRead.subVector(first, last);
917 
918  analogPort.port.setEnvelope(lastStateStamp);
919  analogPort.port.write();
920  }
921  }
922 
923  if (useROS != ROS_disabled && rosMsgType == "geometry_msgs/WrenchStamped")
924  {
925  std::vector<yarp::rosmsg::geometry_msgs::WrenchStamped> rosDataVec;
926  rosDataVec.resize(rosPublisherWrenchPortVec.size());
927 
928  for(size_t i = 0; i < rosDataVec.size(); i++)
929  {
930  rosDataVec.at(i).header.seq = rosMsgCounterVec.at(i)++;
931  rosDataVec.at(i).header.stamp = yarp::os::Time::now();
932  rosDataVec.at(i).header.frame_id = frame_idVec.at(i);
933 
934  rosDataVec.at(i).wrench.force.x = lastDataRead[(rosOffset + 6 + rosPadding) * i + 0];
935  rosDataVec.at(i).wrench.force.y = lastDataRead[(rosOffset + 6 + rosPadding) * i + 1];
936  rosDataVec.at(i).wrench.force.z = lastDataRead[(rosOffset + 6 + rosPadding) * i + 2];
937 
938  rosDataVec.at(i).wrench.torque.x = lastDataRead[(rosOffset + 6 + rosPadding) * i + 3];
939  rosDataVec.at(i).wrench.torque.y = lastDataRead[(rosOffset + 6 + rosPadding) * i + 4];
940  rosDataVec.at(i).wrench.torque.z = lastDataRead[(rosOffset + 6 + rosPadding) * i + 5];
941 
942  rosPublisherWrenchPortVec.at(i).write(rosDataVec.at(i));
943  }
944  }
945  else if (useROS != ROS_disabled && rosMsgType == "sensor_msgs/JointState")
946  {
948  size_t data_size = lastDataRead.size();
949  rosData.name.resize(data_size);
950  rosData.position.resize(data_size);
951  rosData.velocity.resize(data_size);
952  rosData.effort.resize(data_size);
953 
954  if (data_size != ros_joint_names.size())
955  {
956  yCDebug(ANALOGWRAPPER) << "Invalid jointNames size:" << data_size << "!=" << ros_joint_names.size();
957  }
958  else
959  {
960  for (size_t i = 0; i< data_size; i++)
961  {
962  //JointTypeEnum jType;
963  // if (jType == VOCAB_JOINTTYPE_REVOLUTE)
964  {
965  rosData.name[i] = ros_joint_names[i];
966  rosData.position[i] = convertDegreesToRadians(lastDataRead[i]);
967  rosData.velocity[i] = 0;
968  rosData.effort[i] = 0;
969  }
970  }
971  }
972  rosData.header.seq = rosMsgCounterVec.at(0)++;
973  rosData.header.stamp = yarp::os::Time::now();
974  rosPublisherJointPort.write(rosData);
975  }
976  }
977  else
978  {
979  yCError(ANALOGWRAPPER, "AnalogWrapper: %s: vector size non valid: %lu", sensorId.c_str(), static_cast<unsigned long> (lastDataRead.size()));
980  }
981  }
982  else
983  {
984  switch(ret)
985  {
986  case IAnalogSensor::AS_OVF:
987  yCError(ANALOGWRAPPER, "AnalogWrapper: %s: Sensor returned overflow error (code %d).", sensorId.c_str(), ret);
988  break;
989  case IAnalogSensor::AS_TIMEOUT:
990  yCError(ANALOGWRAPPER, "AnalogWrapper: %s: Sensor returned timeout error (code %d).", sensorId.c_str(), ret);
991  break;
992  case IAnalogSensor::AS_ERROR:
993  default:
994  yCError(ANALOGWRAPPER, "AnalogWrapper: %s: Sensor returned error with code %d.", sensorId.c_str(), ret);
995  break;
996  }
997  }
998  }
999 }
1000 
1002 {
1003  yCTrace(ANALOGWRAPPER, "AnalogWrapper::Close");
1004  if (PeriodicThread::isRunning())
1005  {
1006  PeriodicThread::stop();
1007  }
1008 
1009  detachAll();
1010  removeHandlers();
1011 
1012  if(subDeviceOwned)
1013  {
1014  subDeviceOwned->close();
1015  delete subDeviceOwned;
1016  subDeviceOwned = nullptr;
1017  }
1018 
1019  if(rosNode!=nullptr) {
1020  rosNode->interrupt();
1021  delete rosNode;
1022 
1023  rosNode = nullptr;
1024  }
1025 
1026  return true;
1027 }
const yarp::os::LogComponent & ANALOGWRAPPER()
define control board standard interfaces
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:16
constexpr yarp::conf::vocab32_t VOCAB_IANALOG
Definition: IAnalogSensor.h:14
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_CHANNEL
bool ret
static void handler(int sig)
Definition: RFModule.cpp:241
constexpr double DEFAULT_THREAD_PERIOD
A yarp port that output data read from an analog sensor.
std::string port_name
AnalogPortEntry & operator=(const AnalogPortEntry &alt)
yarp::os::BufferedPort< yarp::sig::Vector > port
AnalogPortEntry()
A yarp port that output data read from an analog sensor.
Handler of the rpc port related to an analog sensor.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
AnalogServerHandler(const char *n)
Handler of the rpc port related to an analog sensor.
void setInterface(yarp::dev::IAnalogSensor *is)
bool _handleIAnalog(yarp::os::Bottle &cmd, yarp::os::Bottle &reply)
void threadRelease() override
Release method.
void setId(const std::string &id)
void attach(yarp::dev::IAnalogSensor *s)
bool threadInit() override
Initialization method.
~AnalogWrapper() override
void run() override
Loop function.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
std::string getId()
bool close() override
Close the DeviceDriver.
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which analog sensor this thread has to read from.
bool detachAll() override
Detach the object (you must have first called attach).
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:74
A generic interface to sensors (gyro, a/d converters).
Definition: IAnalogSensor.h:28
virtual int calibrateSensor()=0
Calibrates the whole sensor.
virtual int read(yarp::sig::Vector &out)=0
Read a vector from the sensor.
virtual int getChannels()=0
Get the number of channels of the sensor.
virtual int calibrateChannel(int ch)=0
Calibrates one single channel.
A container for a device driver.
Definition: PolyDriver.h:24
bool close() override
Close the DeviceDriver.
Definition: PolyDriver.cpp:173
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:140
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:164
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:251
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:240
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
Definition: Bottle.cpp:302
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:230
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition: Bottle.cpp:140
bool isNull() const override
Checks if the object is invalid.
Definition: Bottle.cpp:370
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:211
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:287
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
The Node class.
Definition: Node.h:24
void interrupt()
interrupt delegates the call to the Node port interrupt.
Definition: Node.cpp:597
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:25
A mini-server for network communication.
Definition: Port.h:47
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:502
void close() override
Stop port activity.
Definition: Port.cpp:354
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:79
A class for storing options and configuration information.
Definition: Property.h:34
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1046
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:64
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:124
A single value (typically within a Bottle).
Definition: Value.h:45
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isString() const
Checks if value is a string.
Definition: Value.cpp:156
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:228
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual bool isList() const
Checks if value is a list.
Definition: Value.cpp:162
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:240
virtual bool isInt32() const
Checks if value is a 32-bit integer.
Definition: Value.cpp:132
bool isNull() const override
Checks if the object is invalid.
Definition: Value.cpp:380
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
std::vector< std::string > name
Definition: JointState.h:56
std::vector< yarp::conf::float64_t > position
Definition: JointState.h:57
std::vector< yarp::conf::float64_t > velocity
Definition: JointState.h:58
std::vector< yarp::conf::float64_t > effort
Definition: JointState.h:59
yarp::rosmsg::std_msgs::Header header
Definition: JointState.h:55
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
bool write(yarp::os::ConnectionWriter &connection) const override
Write vector to a connection.
Definition: Vector.cpp:79
void resize(size_t size) override
Resize the vector.
Definition: Vector.h:222
size_t size() const
Definition: Vector.h:323
VectorOf< T > subVector(unsigned int first, unsigned int last) const
Creates and returns a new vector, being the portion of the original vector defined by the first and l...
Definition: Vector.h:402
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
An interface for the device drivers.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
An interface to the operating system, including Port based communication.
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
Definition: ImageFile.cpp:922
Signal processing.
Definition: Image.h:22
The main, catch-all namespace for YARP.
Definition: dirs.h:16
@ ROS_only
Definition: yarpRosHelper.h:20
@ ROS_config_error
Definition: yarpRosHelper.h:17
@ ROS_enabled
Definition: yarpRosHelper.h:19
@ ROS_disabled
Definition: yarpRosHelper.h:18
double convertDegreesToRadians(double degrees)
convert degrees to radiants for ROS messages
Definition: yarpRosHelper.h:27