YARP
Yet Another Robot Platform
RgbdSensor_nws_ros.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 #ifndef YARP_DEV_RGBDSENSOR_NWS_ROS_H
7 #define YARP_DEV_RGBDSENSOR_NWS_ROS_H
8 
9 #include <vector>
10 #include <iostream>
11 #include <string>
12 #include <sstream>
13 
14 #include <yarp/os/Port.h>
15 #include <yarp/os/Time.h>
16 #include <yarp/os/Stamp.h>
17 #include <yarp/os/Network.h>
18 #include <yarp/os/Property.h>
19 #include <yarp/os/PeriodicThread.h>
20 
21 #include <yarp/sig/Vector.h>
22 
23 #include <yarp/dev/WrapperSingle.h>
24 #include <yarp/dev/PolyDriver.h>
25 #include <yarp/dev/IRGBDSensor.h>
27 
28 // ROS stuff
29 #include <yarp/os/Node.h>
30 #include <yarp/os/Publisher.h>
31 #include <yarp/os/Subscriber.h>
32 #include <yarp/rosmsg/TickTime.h>
35 
36 #define DEFAULT_THREAD_PERIOD 0.03 // s
37 
38 namespace RGBDImpl
39 {
40  const std::string frameId_param = "frame_Id";
41  const std::string nodeName_param = "nodeName";
42  const std::string colorTopicName_param = "colorTopicName";
43  const std::string depthTopicName_param = "depthTopicName";
44  const std::string depthInfoTopicName_param = "depthInfoTopicName";
45  const std::string colorInfoTopicName_param = "colorInfoTopicName";
46 }
47 
92 {
93 private:
97  typedef unsigned int UInt;
98 
99  enum SensorType{COLOR_SENSOR, DEPTH_SENSOR};
100 
101  template <class T>
102  struct param
103  {
104  param(T& inVar, std::string inName)
105  {
106  var = &inVar;
107  parname = inName;
108  }
109  T* var;
110  std::string parname;
111  };
112 
113  ImageTopicType publisherPort_color;
114  ImageTopicType publisherPort_depth;
115  DepthTopicType publisherPort_colorCaminfo;
116  DepthTopicType publisherPort_depthCaminfo;
117  yarp::os::Node* m_node;
118  std::string nodeName;
119  std::string m_color_frame_id;
120  std::string m_depth_frame_id;
121  yarp::sig::FlexImage colorImage;
123  UInt nodeSeq;
124 
125  // Image data specs
126  // int hDim, vDim;
127  double period;
128  std::string sensorId;
129  yarp::dev::IRGBDSensor* sensor_p;
132  int verbose;
133  bool forceInfoSync;
134  bool initialize_ROS(yarp::os::Searchable& config);
135 
136  // Open the wrapper only, the attach method needs to be called before using it
137  // Typical usage: yarprobotinterface
138  bool openDeferredAttach(yarp::os::Searchable& prop);
139 
140  // If a subdevice parameter is given, the wrapper will open it and attach to immediately.
141  // Typical usage: simulator or command line
142  bool isSubdeviceOwned;
143  yarp::dev::PolyDriver* subDeviceOwned;
144  bool openAndAttachSubDevice(yarp::os::Searchable& prop);
145 
146  // Synch
147  yarp::os::Stamp colorStamp;
148  yarp::os::Stamp depthStamp;
149 
150  bool writeData();
151  bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo,
152  const std::string& frame_id,
153  const UInt& seq,
154  const SensorType& sensorType);
155 
156 public:
162  ~RgbdSensor_nws_ros() override;
163 
164  bool open(yarp::os::Searchable &params) override;
165  bool close() override;
166 
167  void setId(const std::string &id);
168  std::string getId();
169 
173  bool attach(yarp::dev::PolyDriver *poly) override;
174  bool detach() override;
175 
176  bool threadInit() override;
177  void threadRelease() override;
178  void run() override;
179 };
180 
181 #endif // YARP_DEV_RGBDSENSOR_NWS_ROS_H
contains the definition of a Vector type
rgbdSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce two streams o...
bool close() override
Close the DeviceDriver.
void setId(const std::string &id)
RgbdSensor_nws_ros & operator=(RgbdSensor_nws_ros &&)=delete
void threadRelease() override
Release method.
RgbdSensor_nws_ros(RgbdSensor_nws_ros &&)=delete
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
bool open(yarp::os::Searchable &params) override
Device driver interface.
RgbdSensor_nws_ros(const RgbdSensor_nws_ros &)=delete
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool detach() override
WrapperSingle interface.
RgbdSensor_nws_ros & operator=(const RgbdSensor_nws_ros &)=delete
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
Control interface for frame grabber devices.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:40
A container for a device driver.
Definition: PolyDriver.h:24
Helper interface for an object that can wrap/or "attach" to a single other device.
Definition: WrapperSingle.h:32
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:66
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
Image class with user control of representation details.
Definition: Image.h:414
const std::string depthInfoTopicName_param
const std::string depthTopicName_param
const std::string colorTopicName_param
const std::string nodeName_param
const std::string frameId_param
const std::string colorInfoTopicName_param