YARP
Yet Another Robot Platform
RGBDToPointCloudSensor_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_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H
7#define YARP_DEV_RGBDTOPOINTCLOUDSENSOR_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>
20
21#include <yarp/sig/Vector.h>
22
24#include <yarp/dev/PolyDriver.h>
27
28// ROS stuff
29#include <yarp/os/Node.h>
30#include <yarp/os/Publisher.h>
31#include <yarp/os/Subscriber.h>
34
35constexpr double DEFAULT_THREAD_PERIOD = 0.033; // s
36
38 const std::string frameId_param = "frame_Id";
39 const std::string nodeName_param = "nodeName";
40 const std::string pointCloudTopicName_param = "pointCloudTopicName";
41}
80{
81private:
82 // defining types for shorter names
86 typedef unsigned int UInt;
87
88 enum SensorType{COLOR_SENSOR, DEPTH_SENSOR};
89
90 template <class T>
91 struct param
92 {
93 param(T& inVar, std::string inName)
94 {
95 var = &inVar;
96 parname = inName;
97 }
98 T* var;
99 std::string parname;
100 };
101
102 PointCloudTopicType publisherPort_pointCloud;
103 yarp::os::Node* m_node = nullptr;
104 std::string nodeName;
105 std::string pointCloudTopicName;
106 std::string frameId;
107
108 // images from device
109 yarp::sig::FlexImage colorImage;
111 UInt nodeSeq = 0;
112
113
114 // this is the sub device or the real device
115
116 double period = DEFAULT_THREAD_PERIOD;
117 std::string sensorId;
118 yarp::dev::IRGBDSensor* sensor_p = nullptr;
119 yarp::dev::IFrameGrabberControls* fgCtrl = nullptr;
121
122 int verbose = 4;
123 bool forceInfoSync = true;
124 bool initialize_ROS(yarp::os::Searchable& config);
125
126 // Open the wrapper only, the attach method needs to be called before using it
127 // Typical usage: yarprobotinterface
128 bool openDeferredAttach(yarp::os::Searchable& prop);
129
130 // If a subdevice parameter is given, the wrapper will open it and attach to immediately.
131 // Typical usage: simulator or command line
132 bool isSubdeviceOwned = false;
133 yarp::dev::PolyDriver* subDeviceOwned = nullptr;
134 bool openAndAttachSubDevice(yarp::os::Searchable& prop);
135
136 // Synch
137 yarp::os::Stamp colorStamp;
138 yarp::os::Stamp depthStamp;
139 yarp::os::Property m_conf;
140
141 bool writeData();
142
143public:
150
151 bool open(yarp::os::Searchable &params) override;
153 bool close() override;
154
158 bool attach(yarp::dev::PolyDriver *poly) override;
159 bool detach() override;
160
161 bool threadInit() override;
162 void threadRelease() override;
163 void run() override;
164};
165
166#endif // YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H
constexpr double DEFAULT_THREAD_PERIOD
contains the definition of a Vector type
RGBDToPointCloudSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce o...
RGBDToPointCloudSensor_nws_ros(RGBDToPointCloudSensor_nws_ros &&)=delete
bool open(yarp::os::Searchable &params) override
Device driver interface.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
void threadRelease() override
Release method.
bool threadInit() override
Initialization method.
bool close() override
Close the DeviceDriver.
bool detach() override
WrapperSingle interface.
RGBDToPointCloudSensor_nws_ros & operator=(RGBDToPointCloudSensor_nws_ros &&)=delete
RGBDToPointCloudSensor_nws_ros & operator=(const RGBDToPointCloudSensor_nws_ros &)=delete
RGBDToPointCloudSensor_nws_ros(const RGBDToPointCloudSensor_nws_ros &)=delete
bool fromConfig(yarp::os::Searchable &params)
Interface implemented by all device drivers.
Definition: DeviceDriver.h:30
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:39
A container for a device driver.
Definition: PolyDriver.h:23
Helper interface for an object that can wrap/or "attach" to a single other device.
Definition: WrapperSingle.h:31
The Node class.
Definition: Node.h:23
An abstraction for a periodic thread.
A class for storing options and configuration information.
Definition: Property.h:33
A base class for nested structures that can be searched.
Definition: Searchable.h:63
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:21
Image class with user control of representation details.
Definition: Image.h:411
const std::string pointCloudTopicName_param