YARP
Yet Another Robot Platform
GenericSensorRosPublisher.h
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 
7 #ifndef YARP_DEV_GENERICSENSORSROSPUBLISHER_H
8 #define YARP_DEV_GENERICSENSORSROSPUBLISHER_H
9 
10 #include <yarp/os/PeriodicThread.h>
11 #include <yarp/os/Publisher.h>
12 #include <yarp/os/Node.h>
13 #include <yarp/dev/DeviceDriver.h>
16 #include <yarp/os/Log.h>
17 #include <yarp/os/LogComponent.h>
18 #include <yarp/os/LogStream.h>
19 
20 
21 // The log component is defined in each device, with a specialized name
23 
24 
25 
42 template <class ROS_MSG>
47 {
48 protected:
49  double m_periodInS{0.01};
50  std::string m_publisherName;
51  std::string m_rosNodeName;
55  size_t m_msg_counter;
56  double m_timestamp;
57  std::string m_framename;
58  const size_t m_sens_index = 0;
60 
61 public:
64 
65  /* DevideDriver methods */
66  bool open(yarp::os::Searchable &params) override;
67  bool close() override;
68 
69  /* IMultipleWrapper methods */
70  bool attachAll(const yarp::dev::PolyDriverList &p) override;
71  bool detachAll() override;
72 
73  /* PeriodicRateThread methods */
74  void threadRelease() override;
75  void run() override;
76 
77 protected:
78  virtual bool viewInterfaces() = 0;
79 };
80 
81 template <class ROS_MSG>
83  PeriodicThread(0.02)
84 {
85  m_rosNode = nullptr;
86  m_poly = nullptr;
87  m_msg_counter=0;
88  m_timestamp=0;
89 }
90 
91 template <class ROS_MSG>
93 
94 template <class ROS_MSG>
96 {
97  if (!config.check("topic")) {
98  yCError(GENERICSENSORROSPUBLISHER, "Missing `topic` parameter, exiting.");
99  return false;
100  }
101 
102  if (!config.check("period")) {
103  yCError(GENERICSENSORROSPUBLISHER, "Missing `period` parameter, exiting.");
104  return false;
105  }
106 
107  if (config.find("period").isFloat32()==false && config.find("period").isFloat64()==false) {
108  yCError(GENERICSENSORROSPUBLISHER, "`period` parameter is present but it is not a float, exiting.");
109  return false;
110  }
111 
112  m_periodInS = config.find("period").asFloat64();
113 
114  if (m_periodInS <= 0) {
115  yCError(GENERICSENSORROSPUBLISHER, "`period` parameter is present (%f) but it is not a positive value, exiting.", m_periodInS);
116  return false;
117  }
118 
119  std::string name = config.find("topic").asString();
120 
121  // TODO(traversaro) Add port name validation when ready,
122  // see https://github.com/robotology/yarp/pull/1508
123 
124  m_rosNodeName = name+ "_node";
125  m_publisherName = name;
126 
127  if (config.check("node_name"))
128  {
129  m_rosNodeName = config.find("node_name").asString();
130  }
131 
132  if (m_rosNodeName == "")
133  {
134  yCError(GENERICSENSORROSPUBLISHER) << "Invalid node name: " << m_rosNodeName;
135  return false;
136  }
137 
138  m_rosNode = new yarp::os::Node(m_rosNodeName); // add a ROS node
139 
140  if (m_rosNode == nullptr) {
141  yCError(GENERICSENSORROSPUBLISHER) << "Opening " << m_rosNodeName << " Node, check your yarp-ROS network configuration\n";
142  return false;
143  }
144 
145  if (!m_publisher.topic(m_publisherName)) {
146  yCError(GENERICSENSORROSPUBLISHER) << "Opening " << m_publisherName << " Topic, check your yarp-ROS network configuration\n";
147  return false;
148  }
149 
150  if (config.check("subdevice"))
151  {
153  yarp::dev::PolyDriverList driverlist;
154  p.fromString(config.toString(), false);
155  p.put("device", config.find("subdevice").asString());
156 
157  if (!m_subdevicedriver.open(p) || !m_subdevicedriver.isValid())
158  {
159  yCError(GENERICSENSORROSPUBLISHER) << "Failed to open subdevice.. check params";
160  return false;
161  }
162 
163  driverlist.push(&m_subdevicedriver, "1");
164  if (!attachAll(driverlist))
165  {
166  yCError(GENERICSENSORROSPUBLISHER) << "Failed to open subdevice.. check params";
167  return false;
168  }
169  }
170 
171  return true;
172 }
173 
174 template <class ROS_MSG>
176 {
177  return this->detachAll();
178 
179  m_publisher.close();
180  if (m_rosNode)
181  {
182  delete m_rosNode;
183  m_rosNode = nullptr;
184  }
185 }
186 
187 template <class ROS_MSG>
189 {
190  // Attach the device
191  if (p.size() > 1)
192  {
193  yCError(GENERICSENSORROSPUBLISHER, "This device only supports exposing a "
194  "single MultipleAnalogSensors device on YARP ports, but %d devices have been passed in attachAll.",
195  p.size());
196  yCError(GENERICSENSORROSPUBLISHER, "Please use the multipleanalogsensorsremapper device to combine several device in a new device.");
197  detachAll();
198  return false;
199  }
200 
201  if (p.size() == 0)
202  {
203  yCError(GENERICSENSORROSPUBLISHER, "No device passed to attachAll, please pass a device to expose on YARP ports.");
204  return false;
205  }
206 
207  m_poly = p[0]->poly;
208 
209  if (!m_poly)
210  {
211  yCError(GENERICSENSORROSPUBLISHER, "Null pointer passed to attachAll.");
212  return false;
213  }
214 
215  // View all the interfaces
216  bool ok = viewInterfaces();
217 
218  // Set rate period
219  ok &= this->setPeriod(m_periodInS);
220  ok &= this->start();
221 
222  return ok;
223 }
224 
225 template <class ROS_MSG>
227 {
228  // Stop the thread on detach
229  if (this->isRunning()) {
230  this->stop();
231  }
232  return true;
233 }
234 
235 template <class ROS_MSG>
237 {
238 }
239 
240 template <class ROS_MSG>
242 {
243  return;
244 }
245 
246 #endif
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
This abstract template needs to be specialized in a ROS Publisher, for a specific ROS mesagge/sensor ...
yarp::dev::PolyDriver * m_poly
virtual ~GenericSensorRosPublisher()
void run() override
Loop function.
yarp::dev::PolyDriver m_subdevicedriver
bool detachAll() override
Detach the object (you must have first called attach).
virtual bool viewInterfaces()=0
bool attachAll(const yarp::dev::PolyDriverList &p) override
Attach to a list of objects.
yarp::os::Publisher< ROS_MSG > m_publisher
void threadRelease() override
Release method.
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
Interface for an object that can wrap/attach to to another.
void push(PolyDriver *p, const char *k)
A container for a device driver.
Definition: PolyDriver.h:24
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
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
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 yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:150
virtual bool isFloat32() const
Checks if value is a 32-bit floating point number.
Definition: Value.cpp:144
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
#define yCError(component,...)
Definition: LogComponent.h:154
#define YARP_DECLARE_LOG_COMPONENT(name)
Definition: LogComponent.h:74