YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
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>
18
22
23#define DEFAULT_THREAD_PERIOD 20 //ms
24#define RGBDSENSOR_TIMEOUT_DEFAULT 100 //ms
25
26
28
29
51{
52protected:
54private:
57protected:
58
61
62 // Image data specs
64 IRGBDSensor::RGBDSensor_status sensorStatus{IRGBDSensor::RGBD_SENSOR_NOT_READY};
65 int verbose{2};
66
69
70 // This is gonna be superseded by the synchronized when it'll be ready
72
73public:
79 ~RGBDSensorClient() override;
80
81 int getRgbHeight() override;
82 int getRgbWidth() override;
84 bool getRgbResolution(int &width, int &height) override;
85 bool setRgbResolution(int width, int height) override;
86 bool getRgbFOV(double &horizontalFov, double &verticalFov) override;
87 bool setRgbFOV(double horizontalFov, double verticalFov) override;
88 bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override;
89 bool getRgbMirroring(bool& mirror) override;
90 bool setRgbMirroring(bool mirror) override;
91
92 /*
93 * IDepthVisualParams interface. Look at IVisualParams.h for documentation
94 */
95 int getDepthHeight() override;
96 int getDepthWidth() override;
97 bool setDepthResolution(int width, int height) override;
98 bool getDepthFOV(double &horizontalFov, double &verticalFov) override;
99 bool setDepthFOV(double horizontalFov, double verticalFov) override;
100 double getDepthAccuracy() override;
101 bool setDepthAccuracy(double accuracy) override;
102 bool getDepthClipPlanes(double &near, double &far) override;
103 bool setDepthClipPlanes(double near, double far) override;
104 bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override;
105 bool getDepthMirroring(bool& mirror) override;
106 bool setDepthMirroring(bool mirror) override;
107
108 // Device Driver interface //
122 bool open(yarp::os::Searchable& config) override;
123
128 bool close() override;
129
130 /*
131 * IRgbVisualParams interface. Look at IVisualParams.h for documentation
132 */
133
134 /*
135 * IRGBDSensor specific interface methods
136 */
137
144 bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override;
145
152 IRGBDSensor::RGBDSensor_status getSensorStatus() override;
153
159 std::string getLastErrorMsg(yarp::os::Stamp *timeStamp = nullptr) override;
160
173 bool getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp = nullptr) override;
174
188
201
202
203 // IFrame Grabber Control 2
204 //
205 // Implemented by FrameGrabberControls2_Forwarder
206 //
207 using FrameGrabberControls_Forwarder::getCameraDescription;
208 using FrameGrabberControls_Forwarder::hasFeature;
209 using FrameGrabberControls_Forwarder::setFeature;
210 using FrameGrabberControls_Forwarder::getFeature;
211 using FrameGrabberControls_Forwarder::hasOnOff;
212 using FrameGrabberControls_Forwarder::setActive;
213 using FrameGrabberControls_Forwarder::getActive;
214 using FrameGrabberControls_Forwarder::hasAuto;
215 using FrameGrabberControls_Forwarder::hasManual;
216 using FrameGrabberControls_Forwarder::hasOnePush;
217 using FrameGrabberControls_Forwarder::setMode;
218 using FrameGrabberControls_Forwarder::getMode;
219 using FrameGrabberControls_Forwarder::setOnePush;
220};
221
222#endif // YARP_DEV_RGBDSENSORCLIENT_RGBDSENSORCLIENT_H
This class is the parameters parser for class RGBDSensorClient.
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.
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.
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 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.
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.
~RGBDSensorClient() override
bool close() override
Close the DeviceDriver.
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 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.
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
yarp::os::Stamp depthStamp
Interface implemented by all device drivers.
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:31
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:374
Typed image class.
Definition Image.h:616
A class for a Matrix.
Definition Matrix.h:39
constexpr char accuracy[]