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