YARP
Yet Another Robot Platform
RGBDSensorClient.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_RGBDSENSORCLIENT_RGBDSENSORCLIENT_H
7#define YARP_DEV_RGBDSENSORCLIENT_RGBDSENSORCLIENT_H
8
10
11#include <yarp/os/Time.h>
12#include <yarp/os/Network.h>
14
15#include <yarp/dev/PolyDriver.h>
17
21
22#define DEFAULT_THREAD_PERIOD 20 //ms
23#define RGBDSENSOR_TIMEOUT_DEFAULT 100 //ms
24
25
27
28
85{
86protected:
88private:
91protected:
96 std::string image_carrier_type;
97 std::string depth_carrier_type;
98
101
102 // Use a single RPC port for now
105
106 /*
107 * In case the client has to connect to 2 different wrappers/server because the rgb
108 * and depth comes from two different sources.
109 *
110 * It should be possible to attach this guy to more than one port, try to see what
111 * will happen when receiving 2 calls at the same time (receive one calls while serving
112 * another one, it will result in concurrent thread most probably) and buffering issues.
113 *
114
115 std::string local_colorFrame_rpcPort_Name;
116 std::string local_depthFrame_rpcPort_Name;
117 std::string remote_colorFrame_rpcPort_Name;
118 std::string remote_depthFrame_rpcPort_Name;
119
120 yarp::os::Port colorFrame_rpcPort;
121 yarp::os::Port depthFrame_rpcPort;
122 */
123
124 // Image data specs
125 std::string sensorId;
127 IRGBDSensor::RGBDSensor_status sensorStatus{IRGBDSensor::RGBD_SENSOR_NOT_READY};
128 int verbose{2};
129
131
134
135
136 // This is gonna be superseded by the synchronized when it'll be ready
138 bool fromConfig(yarp::os::Searchable &config);
139
140public:
146 ~RGBDSensorClient() override;
147
148 int getRgbHeight() override;
149 int getRgbWidth() override;
151 bool getRgbResolution(int &width, int &height) override;
152 bool setRgbResolution(int width, int height) override;
153 bool getRgbFOV(double &horizontalFov, double &verticalFov) override;
154 bool setRgbFOV(double horizontalFov, double verticalFov) override;
155 bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override;
156 bool getRgbMirroring(bool& mirror) override;
157 bool setRgbMirroring(bool mirror) override;
158
159 /*
160 * IDepthVisualParams interface. Look at IVisualParams.h for documentation
161 */
162 int getDepthHeight() override;
163 int getDepthWidth() override;
164 bool setDepthResolution(int width, int height) override;
165 bool getDepthFOV(double &horizontalFov, double &verticalFov) override;
166 bool setDepthFOV(double horizontalFov, double verticalFov) override;
167 double getDepthAccuracy() override;
168 bool setDepthAccuracy(double accuracy) override;
169 bool getDepthClipPlanes(double &near, double &far) override;
170 bool setDepthClipPlanes(double near, double far) override;
171 bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override;
172 bool getDepthMirroring(bool& mirror) override;
173 bool setDepthMirroring(bool mirror) override;
174
175 // Device Driver interface //
189 bool open(yarp::os::Searchable& config) override;
190
195 bool close() override;
196
197 /*
198 * IRgbVisualParams interface. Look at IVisualParams.h for documentation
199 */
200
201 /*
202 * IRGBDSensor specific interface methods
203 */
204
211 bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override;
212
219 IRGBDSensor::RGBDSensor_status getSensorStatus() override;
220
226 std::string getLastErrorMsg(yarp::os::Stamp *timeStamp = nullptr) override;
227
240 bool getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp = nullptr) override;
241
255
268
269
270 // IFrame Grabber Control 2
271 //
272 // Implemented by FrameGrabberControls2_Forwarder
273 //
274 using FrameGrabberControls_Forwarder::getCameraDescription;
275 using FrameGrabberControls_Forwarder::hasFeature;
276 using FrameGrabberControls_Forwarder::setFeature;
277 using FrameGrabberControls_Forwarder::getFeature;
278 using FrameGrabberControls_Forwarder::hasOnOff;
279 using FrameGrabberControls_Forwarder::setActive;
280 using FrameGrabberControls_Forwarder::getActive;
281 using FrameGrabberControls_Forwarder::hasAuto;
282 using FrameGrabberControls_Forwarder::hasManual;
283 using FrameGrabberControls_Forwarder::hasOnePush;
284 using FrameGrabberControls_Forwarder::setMode;
285 using FrameGrabberControls_Forwarder::getMode;
286 using FrameGrabberControls_Forwarder::setOnePush;
287};
288
289#endif // YARP_DEV_RGBDSENSORCLIENT_RGBDSENSORCLIENT_H
RGBDSensorClient: A Network client to receive data from kinect-like devices. This device will read fr...
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
std::string remote_colorFrame_StreamingPort_name
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
int getDepthWidth() override
Return the height of each frame.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
RgbImageBufferedPort colorFrame_StreamingPort
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
yarp::dev::IRGBDSensor * sensor_p
RGBDSensorClient & operator=(const RGBDSensorClient &)=delete
std::string getLastErrorMsg(yarp::os::Stamp *timeStamp=nullptr) override
Return an error message in case of error.
bool getDepthClipPlanes(double &near, double &far) override
Get the clipping planes of the sensor.
std::string local_colorFrame_StreamingPort_name
RGBDSensorClient(RGBDSensorClient &&)=delete
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
RGBDSensorClient & operator=(RGBDSensorClient &&)=delete
IRGBDSensor::RGBDSensor_status sensorStatus
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
int getRgbWidth() override
Return the width of each frame.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool initialize_YARP(yarp::os::Searchable &config)
bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr) override
Get the both the color and depth frame in a single call.
bool setDepthClipPlanes(double near, double far) override
Set the clipping planes of the sensor.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
std::string remote_depthFrame_StreamingPort_name
bool getDepthImage(yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr) override
Get the depth frame from the device.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
std::string remote_rpcPort_name
~RGBDSensorClient() override
bool close() override
Close the DeviceDriver.
std::string local_rpcPort_name
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
RGBDSensorClient(const RGBDSensorClient &)=delete
bool getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
yarp::os::Port rpcPort
RGBDSensor_StreamingMsgParser * streamingReader
yarp::os::Stamp colorStamp
bool fromConfig(yarp::os::Searchable &config)
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
int getDepthHeight() override
Return the height of each frame.
IRGBDSensor::RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
std::string sensorId
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool open(yarp::os::Searchable &config) override
Create and configure a device, by name.
int getRgbHeight() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
FloatImageBufferedPort depthFrame_StreamingPort
std::string local_depthFrame_StreamingPort_name
std::string depth_carrier_type
std::string image_carrier_type
yarp::os::Stamp depthStamp
Interface implemented by all device drivers.
Definition: DeviceDriver.h:30
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:39
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:63
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:21
This classes implement a sender / parser for IFrameGrabberControls interface messages.
Image class with user control of representation details.
Definition: Image.h:411
A class for a Matrix.
Definition: Matrix.h:39