YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RGBDSensor_nwc_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_NWC_YARP_H
7#define YARP_DEV_RGBDSENSOR_NWC_YARP_H
8
10
11#include <yarp/os/Time.h>
12#include <yarp/os/Network.h>
14
15#include <yarp/dev/PolyDriver.h>
19
20#include "RGBDSensorMsgs.h"
21
22#define DEFAULT_THREAD_PERIOD 20 //ms
23#define RGBDSENSOR_TIMEOUT_DEFAULT 100 //ms
24
25
27
28
48{
49protected:
51
52protected:
55
56 std::mutex m_mutex;
58
59 // Image data specs
61 IRGBDSensor::RGBDSensor_status sensorStatus{IRGBDSensor::RGBD_SENSOR_NOT_READY};
62 int verbose{2};
63
66
67 // This is gonna be superseded by the synchronized when it'll be ready
69
70public:
76 ~RGBDSensor_nwc_yarp() override;
77
78 /*
79 * IRgbVisualParams interface. Look at IVisualParams.h for documentation
80 */
81 int getRgbHeight() override;
82 int getRgbWidth() override;
83 yarp::dev::ReturnValue getRgbSupportedConfigurations(std::vector<yarp::dev::CameraConfig> &configurations) override;
84 yarp::dev::ReturnValue getRgbResolution(int &width, int &height) override;
85 yarp::dev::ReturnValue setRgbResolution(int width, int height) override;
86 yarp::dev::ReturnValue getRgbFOV(double &horizontalFov, double &verticalFov) override;
87 yarp::dev::ReturnValue setRgbFOV(double horizontalFov, double verticalFov) override;
89 yarp::dev::ReturnValue getRgbMirroring(bool& mirror) override;
90 yarp::dev::ReturnValue 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 yarp::dev::ReturnValue getDepthResolution(int& width, int& height) override;
98 yarp::dev::ReturnValue setDepthResolution(int width, int height) override;
99 yarp::dev::ReturnValue getDepthFOV(double &horizontalFov, double &verticalFov) override;
100 yarp::dev::ReturnValue setDepthFOV(double horizontalFov, double verticalFov) override;
103 yarp::dev::ReturnValue getDepthClipPlanes(double &near, double &far) override;
104 yarp::dev::ReturnValue setDepthClipPlanes(double near, double far) override;
106 yarp::dev::ReturnValue getDepthMirroring(bool& mirror) override;
107 yarp::dev::ReturnValue setDepthMirroring(bool mirror) override;
108
109 /*
110 * Device Driver interface
111 */
112 bool open(yarp::os::Searchable& config) override;
113 bool close() override;
114
115 /*
116 * IRGBDSensor specific interface methods
117 */
119 yarp::dev::ReturnValue getSensorStatus(IRGBDSensor::RGBDSensor_status& status) override;
120 yarp::dev::ReturnValue getLastErrorMsg(std::string& message, yarp::os::Stamp *timeStamp = nullptr) override;
121 yarp::dev::ReturnValue getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp = nullptr) override;
124
125 /*
126 * IFrameGrabberControls specific interface methods
127 */
132 yarp::dev::ReturnValue setFeature(yarp::dev::cameraFeature_id_t feature, double value1, double value2) override;
133 yarp::dev::ReturnValue getFeature(yarp::dev::cameraFeature_id_t feature, double& value1, double& value2) override;
143
144};
145
146#endif // YARP_DEV_RGBDSENSOR_NWC_YARP_H
CameraDescriptor camera
FeatureMode mode
This class is the parameters parser for class RGBDSensor_nwc_yarp.
RGBDSensor_nwc_yarp: A Network client to receive data from kinect-like devices.
RgbImageBufferedPort m_colorFrame_StreamingPort
yarp::os::Stamp depthStamp
FloatImageBufferedPort m_depthFrame_StreamingPort
bool close() override
Close the DeviceDriver.
yarp::dev::ReturnValue setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
yarp::dev::ReturnValue getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
yarp::dev::ReturnValue getRgbSupportedConfigurations(std::vector< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
yarp::dev::ReturnValue setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
yarp::dev::ReturnValue getActive(yarp::dev::cameraFeature_id_t feature, bool &isActive) override
Get the current status of the feature, on or off.
yarp::dev::ReturnValue setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
int getRgbHeight() override
Return the height of each frame.
yarp::dev::ReturnValue setActive(yarp::dev::cameraFeature_id_t feature, bool onoff) override
Set the requested feature on or off.
RGBDSensor_nwc_yarp & operator=(RGBDSensor_nwc_yarp &&)=delete
yarp::dev::ReturnValue getFeature(yarp::dev::cameraFeature_id_t feature, double &value) override
Get the current value for the requested feature.
RGBDSensor_nwc_yarp(const RGBDSensor_nwc_yarp &)=delete
yarp::dev::ReturnValue getDepthClipPlanes(double &near, double &far) override
Get the clipping planes of the sensor.
yarp::dev::ReturnValue getDepthIntrinsicParam(yarp::os::Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
yarp::dev::ReturnValue getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
int getDepthHeight() override
Return the height of each frame.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
yarp::dev::ReturnValue setFeature(yarp::dev::cameraFeature_id_t feature, double value) override
Set the requested feature to a value (saturation, brightness ... )
yarp::dev::ReturnValue getRgbIntrinsicParam(yarp::os::Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
int getDepthWidth() override
Return the height of each frame.
yarp::dev::ReturnValue getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
yarp::dev::ReturnValue getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
yarp::dev::ReturnValue getDepthResolution(int &width, int &height) override
Get the resolution of the depth image from the camera.
yarp::dev::ReturnValue getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
yarp::dev::ReturnValue setMode(yarp::dev::cameraFeature_id_t feature, yarp::dev::FeatureMode mode) override
Set the requested mode for the feature.
yarp::os::Stamp colorStamp
yarp::dev::ReturnValue getCameraDescription(yarp::dev::CameraDescriptor &camera) override
Get a basic description of the camera hw.
yarp::dev::ReturnValue getSensorStatus(IRGBDSensor::RGBDSensor_status &status) override
yarp::dev::ReturnValue getLastErrorMsg(std::string &message, yarp::os::Stamp *timeStamp=nullptr) override
Return an error message in case of error.
yarp::dev::ReturnValue setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
yarp::dev::ReturnValue getDepthAccuracy(double &accuracy) override
Get the minimum detectable variation in distance [meter].
RGBDSensorMsgs m_rgbdsensor_RPC
yarp::dev::ReturnValue getDepthImage(yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr) override
Get the depth frame from the device.
RGBDSensor_nwc_yarp(RGBDSensor_nwc_yarp &&)=delete
yarp::dev::ReturnValue getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
yarp::dev::ReturnValue getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
yarp::dev::ReturnValue setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
yarp::dev::ReturnValue setOnePush(yarp::dev::cameraFeature_id_t feature) override
Set the requested feature to a value (saturation, brightness ... )
yarp::dev::IRGBDSensor * sensor_p
RGBDSensor_StreamingMsgParser * streamingReader
yarp::dev::ReturnValue getMode(yarp::dev::cameraFeature_id_t feature, yarp::dev::FeatureMode &mode) override
Get the current mode for the feature.
yarp::dev::ReturnValue 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.
int getRgbWidth() override
Return the width of each frame.
RGBDSensor_nwc_yarp & operator=(const RGBDSensor_nwc_yarp &)=delete
yarp::dev::ReturnValue setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
yarp::dev::ReturnValue setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
IRGBDSensor::RGBDSensor_status sensorStatus
yarp::dev::ReturnValue setDepthClipPlanes(double near, double far) override
Set the clipping planes of the sensor.
Interface implemented by all device drivers.
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 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
Image class with user control of representation details.
Definition Image.h:361
Typed image class.
Definition Image.h:603
A class for a Matrix.
Definition Matrix.h:39
constexpr char accuracy[]