YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RgbdSensor_nws_yarp.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_YARP_H
7#define YARP_DEV_RGBDSENSOR_NWS_YARP_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/Bottle.h>
18#include <yarp/os/Network.h>
19#include <yarp/os/Property.h>
22
23
24#include <yarp/sig/Vector.h>
25
27#include <yarp/dev/PolyDriver.h>
29
33
34namespace RGBDImpl {
35
36#define DEFAULT_THREAD_PERIOD 0.03 // s
37
38// Following three definitions would fit better in a header file
39// shared between client and server ... where to place it?
41#define RGBD_WRAPPER_PROTOCOL_VERSION_MAJOR 1
42#define RGBD_WRAPPER_PROTOCOL_VERSION_MINOR 0
43
44
45
63
64} // namespace RGBDImpl
65
100{
101private:
105 typedef unsigned int UInt;
106
107 enum SensorType{COLOR_SENSOR, DEPTH_SENSOR};
108
109 template <class T>
110 struct param
111 {
112 param(T& inVar, std::string inName)
113 {
114 var = &inVar;
115 parname = inName;
116 }
117 T* var;
118 std::string parname;
119 };
120
121 std::string colorFrame_StreamingPort_Name;
122 std::string depthFrame_StreamingPort_Name;
123 ImagePortType colorFrame_StreamingPort;
124 DepthPortType depthFrame_StreamingPort;
125
126 // One RPC port should be enough for the wrapper in all cases
127 yarp::os::Port rpcPort;
128 std::string rpcPort_Name;
129 std::string nodeName;
130 yarp::sig::FlexImage colorImage;
132
133 // It should be possible to attach this guy to more than one port, try to see what
134 // will happen when receiving 2 calls at the same time (receive one calls while serving
135 // another one, it will result in concurrent thread most probably) and buffering issues.
136// sensor::depth::RGBDSensor_RPCMgsParser RPC_parser;
137
138 //Helper class for RPCs
140
141 // Image data specs
142 // int hDim, vDim;
143 double period;
144 std::string sensorId;
145 yarp::dev::IRGBDSensor* sensor_p;
148 int verbose;
149 bool initialize_YARP(yarp::os::Searchable& config);
150
151 // Open the wrapper only, the attach method needs to be called before using it
152 // Typical usage: yarprobotinterface
153 bool openDeferredAttach(yarp::os::Searchable& prop);
154
155 // If a subdevice parameter is given, the wrapper will open it and attach to immediately.
156 // Typical usage: simulator or command line
157 bool isSubdeviceOwned;
158 yarp::dev::PolyDriver* subDeviceOwned;
159 bool openAndAttachSubDevice(yarp::os::Searchable& prop);
160
161 // Synch
162 yarp::os::Stamp colorStamp;
163 yarp::os::Stamp depthStamp;
164 yarp::os::Property m_conf;
165
166 bool writeData();
167 bool setCamInfo(const std::string& frame_id,
168 const UInt& seq,
169 const SensorType& sensorType);
170
171public:
177 ~RgbdSensor_nws_yarp() override;
178
179 bool open(yarp::os::Searchable &params) override;
180 bool fromConfig(yarp::os::Searchable &params);
181 bool close() override;
182
187 bool attach(yarp::dev::PolyDriver *poly) override;
188 bool detach() override;
189
190 bool threadInit() override;
191 void threadRelease() override;
192 void run() override;
193};
194
195#endif // YARP_DEV_RGBDSENSOR_NWS_YARP_H
contains the definition of a Vector type
bool configure(yarp::dev::IRGBDSensor *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
~RGBDSensorParser() override=default
rgbdSensor_nws_yarp: A Network grabber for kinect-like devices. This device will produce two streams ...
void run() override
Loop function.
bool threadInit() override
Initialization method.
RgbdSensor_nws_yarp & operator=(RgbdSensor_nws_yarp &&)=delete
bool detach() override
WrapperSingle interface.
RgbdSensor_nws_yarp(RgbdSensor_nws_yarp &&)=delete
bool fromConfig(yarp::os::Searchable &params)
bool close() override
Close the DeviceDriver.
RgbdSensor_nws_yarp(const RgbdSensor_nws_yarp &)=delete
RgbdSensor_nws_yarp & operator=(const RgbdSensor_nws_yarp &)=delete
bool open(yarp::os::Searchable &params) override
Device driver interface.
void threadRelease() override
Release method.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
Interface implemented by all device drivers.
A cheap and cheerful framework for human readable/writable forms of messages to devices.
An interface for retrieving intrinsic parameter from a depth camera.
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
An interface for retrieving intrinsic parameter from a rgb camera.
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.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:64
A mini-server for performing network communication in the background.
An abstraction for a periodic thread.
A mini-server for network communication.
Definition Port.h:46
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:56
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:374
Typed image class.
Definition Image.h:616
constexpr yarp::conf::vocab32_t VOCAB_PROTOCOL_VERSION
std::int32_t vocab32_t
Definition numeric.h:78
constexpr yarp::conf::vocab32_t createVocab32(char a, char b=0, char c=0, char d=0)
Create a vocab from chars.
Definition Vocab.h:27