6#ifndef YARP_DEV_IRGBDSENSOR_H
7#define YARP_DEV_IRGBDSENSOR_H
47 RGBD_SENSOR_NOT_READY = 0,
48 RGBD_SENSOR_OK_STANDBY = 1,
49 RGBD_SENSOR_OK_IN_USE = 2,
51 DEPTH_SENSOR_ERROR = 4,
52 RGBD_SENSOR_GENERIC_ERROR = 5,
53 RGBD_SENSOR_TIMEOUT = 6
66 bool getRgbFOV(
double &horizontalFov,
double &verticalFov)
override = 0;
67 bool setRgbFOV(
double horizontalFov,
double verticalFov)
override = 0;
76 bool getDepthFOV(
double &horizontalFov,
double &verticalFov)
override = 0;
77 bool setDepthFOV(
double horizontalFov,
double verticalFov)
override = 0;
contains the definition of a Matrix type
An interface for retrieving intrinsic parameter from a depth camera.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
virtual std::string getLastErrorMsg(yarp::os::Stamp *timeStamp=nullptr)=0
Return an error message in case of error.
bool setRgbResolution(int width, int height) override=0
Set the resolution of the rgb image from the camera.
bool setDepthAccuracy(double accuracy) override=0
Set the minimum detectable variation in distance [meter] when possible.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool setDepthResolution(int width, int height) override=0
Set the resolution of the depth image from the camera.
virtual bool getDepthImage(yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=0
Get the depth frame from the device.
int getRgbWidth() override=0
Return the width of each frame.
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
int getDepthWidth() override=0
Return the height of each frame.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override=0
Get the clipping planes of the sensor.
virtual bool getExtrinsicParam(yarp::sig::Matrix &extrinsic)=0
Get the extrinsic parameters from the device.
int getRgbHeight() override=0
Return the height of each frame.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override=0
Get the field of view (FOV) of the depth camera.
virtual bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0
Get the both the color and depth frame in a single call.
bool setDepthClipPlanes(double nearPlane, double farPlane) override=0
Set the clipping planes of the sensor.
virtual bool getRgbImage(yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr)=0
Get the rgb frame from the device.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override=0
Get the field of view (FOV) of the rgb camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override=0
Set the field of view (FOV) of the rgb camera.
double getDepthAccuracy() override=0
Get the minimum detectable variation in distance [meter].
virtual RGBDSensor_status getSensorStatus()=0
Get the surrent status of the sensor, using enum type.
int getDepthHeight() override=0
Return the height of each frame.
bool setDepthFOV(double horizontalFov, double verticalFov) override=0
Set the field of view (FOV) of the depth camera.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the depth camera.
An interface for retrieving intrinsic parameter from a rgb camera.
A class for storing options and configuration information.
An abstraction for a time stamp and/or sequence number.
Image class with user control of representation details.
For streams capable of holding different kinds of content, check what they actually have.
constexpr char accuracy[]