|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
19 #ifndef DEPTHCAMERA_DRIVER_H
20 #define DEPTHCAMERA_DRIVER_H
37 #define RAD2DEG (180/3.14159265359)
41 #define DEG2RAD (3.14159265359/180.0)
211 bool close()
override;
219 bool getRgbFOV(
double& horizontalFov,
double& verticalFov)
override;
220 bool setRgbFOV(
double horizontalFov,
double verticalFov)
override;
228 bool getDepthFOV(
double& horizontalFov,
double& verticalFov)
override;
229 bool setDepthFOV(
double horizontalFov,
double verticalFov)
override;
250 bool setFeature(
int feature,
double value)
override;
251 bool getFeature(
int feature,
double* value)
override;
252 bool setFeature(
int feature,
double value1,
double value2)
override;
253 bool getFeature(
int feature,
double* value1,
double* value2)
override;
254 bool hasOnOff(
int feature,
bool* HasOnOff)
override;
255 bool setActive(
int feature,
bool onoff)
override;
256 bool getActive(
int feature,
bool* isActive)
override;
266 inline bool initializeOpeNIDevice();
267 inline bool setParams();
270 bool setResolution(
int w,
int h, openni::VideoStream& stream);
271 bool setFOV(
double horizontalFov,
double verticalFov, openni::VideoStream& stream);
273 void settingErrorMsg(
const std::string& error,
bool&
ret);
276 openni::VideoStream m_depthStream;
277 openni::VideoStream m_imageStream;
278 openni::Device m_device;
281 std::string m_lastError;
283 bool m_depthRegistration;
284 std::vector<cameraFeature_id_t> m_supportedFeatures;
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.
A base class for nested structures that can be searched.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
int getRgbWidth() override
Return the width of each frame.
Interface implemented by all device drivers.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
contains the definition of a Matrix type
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
int getDepthHeight() override
Return the height of each frame.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
int getDepthWidth() override
Return the height of each frame.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
Image class with user control of representation details.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
depthCamera: YARP driver for OpenNI2 compatible devices.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
int getRgbHeight() override
Return the height of each frame.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
Control interface for frame grabber devices.
static int pixFormatToCode(openni::PixelFormat p)
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
The RGBDSensorParamParser class.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
An abstraction for a time stamp and/or sequence number.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool close() override
Close the DeviceDriver.
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
define common interfaces to discover remote camera capabilities
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
A class for storing options and configuration information.
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.