YARP
Yet Another Robot Platform
fakeDepthCameraDriver.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef YARP_FAKEDEPTHCAMERADRIVER_H
10 #define YARP_FAKEDEPTHCAMERADRIVER_H
11 
12 #include <string>
13 #include <yarp/dev/DeviceDriver.h>
14 #include <yarp/sig/all.h>
15 #include <yarp/sig/Matrix.h>
16 #include <yarp/os/Stamp.h>
17 #include <yarp/dev/IRGBDSensor.h>
19 #include <yarp/dev/PolyDriver.h>
20 
21 
25 {
26 private:
28  typedef yarp::os::Stamp Stamp;
31 
32 public:
35 
36  // DeviceDriver
37  bool open(yarp::os::Searchable& config) override;
38  bool close() override;
39 
40  // IRGBDSensor
41  int getRgbHeight() override;
42  int getRgbWidth() override;
44  bool getRgbResolution(int& width, int& height) override;
45  bool setRgbResolution(int width, int height) override;
46  bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
47  bool setRgbFOV(double horizontalFov, double verticalFov) override;
48  bool getRgbMirroring(bool& mirror) override;
49  bool setRgbMirroring(bool mirror) override;
50 
51  bool getRgbIntrinsicParam(Property& intrinsic) override;
52  int getDepthHeight() override;
53  int getDepthWidth() override;
54  bool setDepthResolution(int width, int height) override;
55  bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
56  bool setDepthFOV(double horizontalFov, double verticalFov) override;
57  bool getDepthIntrinsicParam(Property& intrinsic) override;
58  double getDepthAccuracy() override;
59  bool setDepthAccuracy(double accuracy) override;
60  bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
61  bool setDepthClipPlanes(double nearPlane, double farPlane) override;
62  bool getDepthMirroring(bool& mirror) override;
63  bool setDepthMirroring(bool mirror) override;
64 
65 
66  bool getExtrinsicParam(yarp::sig::Matrix& extrinsic) override;
67  bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = NULL) override;
68  bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = NULL) override;
69  bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp=NULL, Stamp* depthStamp=NULL) override;
70 
72  std::string getLastErrorMsg(Stamp* timeStamp = NULL) override;
73 
74 private:
75  double rgb_h{480};
76  double rgb_w{640};
77  double dep_h{480};
78  double dep_w{640};
79  double accuracy{0.001};
80  double rgb_Vfov{36};
81  double rgb_Hfov{50};
82  double dep_Vfov{36};
83  double dep_Hfov{50};
84  double dep_near{0.4};
85  double dep_far{6};
86 
88  yarp::dev::PolyDriver testgrabber;
90 };
91 #endif // YARP_FAKEDEPTHCAMERADRIVER_H
define common interfaces to discover remote camera capabilities
contains the definition of a Matrix type
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
int getRgbHeight() override
Return the height of each frame.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool close() override
Close the DeviceDriver.
int getDepthWidth() override
Return the height of each frame.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
int getDepthHeight() override
Return the height of each frame.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
int getRgbWidth() override
Return the width of each frame.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
Read a YARP-format image from a device.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:56
A container for a device driver.
Definition: PolyDriver.h:27
A class for storing options and configuration information.
Definition: Property.h:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
Image class with user control of representation details.
Definition: Image.h:403
A class for a Matrix.
Definition: Matrix.h:46