|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
9 #ifndef YARP_FAKEDEPTHCAMERADRIVER_H
10 #define YARP_FAKEDEPTHCAMERADRIVER_H
42 bool close()
override;
50 bool getRgbFOV(
double& horizontalFov,
double& verticalFov)
override;
51 bool setRgbFOV(
double horizontalFov,
double verticalFov)
override;
59 bool getDepthFOV(
double& horizontalFov,
double& verticalFov)
override;
60 bool setDepthFOV(
double horizontalFov,
double verticalFov)
override;
83 double accuracy{0.001};
95 #endif // YARP_FAKEDEPTHCAMERADRIVER_H
A base class for nested structures that can be searched.
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
Interface implemented by all device drivers.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
contains the definition of a Matrix type
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
fakeDepthCamera: Documentation to be added
int getDepthHeight() override
Return the height of each frame.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
Read a YARP-format image from a device.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
Image class with user control of representation details.
A container for a device driver.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
int getRgbWidth() override
Return the width of each frame.
int getRgbHeight() override
Return the height of each frame.
define common interfaces to discover remote camera capabilities
An abstraction for a time stamp and/or sequence number.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
int getDepthWidth() override
Return the height of each frame.
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 getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool close() override
Close the DeviceDriver.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
A class for storing options and configuration information.
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.