YARP  2.3.68+220-20170323.2+git4955ef0
Yet Another Robot Platform
yarp::dev::depthCameraDriver Class Reference

This device is a YARP plugin for OpenNI2 compatible devices, and exposes the IRGBDSensor and IFrameGrabberControls2 interfaces to read the images and operate on available settings. More...

#include <depthCamera/depthCameraDriver.h>

+ Inheritance diagram for yarp::dev::depthCameraDriver:

Public Member Functions

 depthCameraDriver ()
 
 ~depthCameraDriver ()
 
virtual bool open (yarp::os::Searchable &config)
 Open the DeviceDriver. More...
 
virtual bool close ()
 Close the DeviceDriver. More...
 
virtual int getRgbHeight ()
 Return the height of each frame. More...
 
virtual int getRgbWidth ()
 Return the width of each frame. More...
 
virtual bool setRgbResolution (int width, int height)
 Set the resolution of the rgb image from the camera. More...
 
virtual bool getRgbFOV (double &horizontalFov, double &verticalFov)
 Get the field of view (FOV) of the rgb camera. More...
 
virtual bool setRgbFOV (double horizontalFov, double verticalFov)
 Set the field of view (FOV) of the rgb camera. More...
 
virtual bool getRgbMirroring (bool &mirror)
 Get the mirroring setting of the sensor. More...
 
virtual bool setRgbMirroring (bool mirror)
 Set the mirroring setting of the sensor. More...
 
virtual bool getRgbIntrinsicParam (Property &intrinsic)
 
virtual int getDepthHeight ()
 Return the height of each frame. More...
 
virtual int getDepthWidth ()
 Return the height of each frame. More...
 
virtual bool setDepthResolution (int width, int height)
 Set the resolution of the depth image from the camera. More...
 
virtual bool getDepthFOV (double &horizontalFov, double &verticalFov)
 Get the field of view (FOV) of the depth camera. More...
 
virtual bool setDepthFOV (double horizontalFov, double verticalFov)
 Set the field of view (FOV) of the depth camera. More...
 
virtual bool getDepthIntrinsicParam (Property &intrinsic)
 
virtual double getDepthAccuracy ()
 Get the accuracy of the depth measure in [meter]. More...
 
virtual bool setDepthAccuracy (double accuracy)
 Set the accuracy of the depth measure in [meter] when possible. More...
 
virtual bool getDepthClipPlanes (double &nearPlane, double &farPlane)
 Get the clipping planes of the sensor. More...
 
virtual bool setDepthClipPlanes (double nearPlane, double farPlane)
 Set the clipping planes of the sensor. More...
 
virtual bool getDepthMirroring (bool &mirror)
 Get the mirroring setting of the sensor. More...
 
virtual bool setDepthMirroring (bool mirror)
 Set the mirroring setting of the sensor. More...
 
virtual bool getExtrinsicParam (sig::Matrix &extrinsic)
 Get the extrinsic parameters ofrom the device. More...
 
virtual bool getRgbImage (FlexImage &rgbImage, Stamp *timeStamp=NULL)
 
virtual bool getDepthImage (depthImage &depthImage, Stamp *timeStamp=NULL)
 
virtual bool getImages (FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL)
 
virtual RGBDSensor_status getSensorStatus ()
 Get the surrent status of the sensor, using enum type. More...
 
virtual yarp::os::ConstString getLastErrorMsg (Stamp *timeStamp=NULL)
 
virtual bool getCameraDescription (CameraDescriptor *camera)
 Get a basic description of the camera hw. More...
 
virtual bool hasFeature (int feature, bool *hasFeature)
 Check if camera has the requested feature (saturation, brightness ... More...
 
virtual bool setFeature (int feature, double value)
 Set the requested feature to a value (saturation, brightness ... More...
 
virtual bool getFeature (int feature, double *value)
 Get the current value for the requested feature. More...
 
virtual bool setFeature (int feature, double value1, double value2)
 Set the requested feature to a value using 2 params (like white balance) More...
 
virtual bool getFeature (int feature, double *value1, double *value2)
 Get the current value for the requested feature. More...
 
virtual bool hasOnOff (int feature, bool *HasOnOff)
 Check if the camera has the ability to turn on/off the requested feature. More...
 
virtual bool setActive (int feature, bool onoff)
 Set the requested feature on or off. More...
 
virtual bool getActive (int feature, bool *isActive)
 Get the current status of the feature, on or off. More...
 
virtual bool hasAuto (int feature, bool *hasAuto)
 Check if the requested feature has the 'auto' mode. More...
 
virtual bool hasManual (int feature, bool *hasManual)
 Check if the requested feature has the 'manual' mode. More...
 
virtual bool hasOnePush (int feature, bool *hasOnePush)
 Check if the requested feature has the 'onePush' mode. More...
 
virtual bool setMode (int feature, FeatureMode mode)
 Set the requested mode for the feature. More...
 
virtual bool getMode (int feature, FeatureMode *mode)
 Get the current mode for the feature. More...
 
virtual bool setOnePush (int feature)
 Set the requested feature to a value (saturation, brightness ... More...
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
virtual ~DeviceDriver ()
 Destructor. More...
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver. More...
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others. More...
 
- Public Member Functions inherited from yarp::os::IConfig
virtual ~IConfig ()
 Destructor. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 
- Public Member Functions inherited from yarp::dev::IRGBDSensor
virtual ~IRGBDSensor ()
 
virtual bool getRgbIntrinsicParam (yarp::os::Property &intrinsic)=0
 Get the intrinsic parameters of the rgb camera. More...
 
virtual bool getDepthIntrinsicParam (yarp::os::Property &intrinsic)=0
 Get the intrinsic parameters of the depth camera. More...
 
virtual yarp::os::ConstString getLastErrorMsg (yarp::os::Stamp *timeStamp=NULL)=0
 Return an error message in case of error. More...
 
virtual bool getRgbImage (yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=NULL)=0
 Get the rgb frame from the device. More...
 
virtual bool getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=NULL)=0
 Get the depth frame from the device. More...
 
virtual bool getImages (yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=NULL, yarp::os::Stamp *depthStamp=NULL)=0
 Get the both the color and depth frame in a single call. More...
 
- Public Member Functions inherited from yarp::dev::IRgbVisualParams
virtual ~IRgbVisualParams ()
 
- Public Member Functions inherited from yarp::dev::IDepthVisualParams
virtual ~IDepthVisualParams ()
 
- Public Member Functions inherited from yarp::dev::IFrameGrabberControls2
virtual ~IFrameGrabberControls2 ()
 
yarp::os::ConstString busType2String (BusType type)
 
FeatureMode toFeatureMode (bool _auto)
 

Static Public Member Functions

static int pixFormatToCode (openni::PixelFormat p)
 

Private Types

typedef yarp::sig::ImageOf< yarp::sig::PixelFloatdepthImage
 

Additional Inherited Members

- Public Types inherited from yarp::dev::IRGBDSensor
enum  RGBDSensor_status {
  RGBD_SENSOR_NOT_READY = 0,
  RGBD_SENSOR_OK_STANBY = 1,
  RGBD_SENSOR_OK_IN_USE = 2,
  RGB_SENSOR_ERROR = 3,
  DEPTH_SENSOR_ERROR = 4,
  RGBD_SENSOR_GENERIC_ERROR = 5,
  RGBD_SENSOR_TIMEOUT = 6
}
 

Detailed Description

This device is a YARP plugin for OpenNI2 compatible devices, and exposes the IRGBDSensor and IFrameGrabberControls2 interfaces to read the images and operate on available settings.

See they documentation for more details about each interface.

This device is paired with its server called RGBDSensorWrapper to stream the images and perform remote operations.

The config file is subdivided into 5 major sections called "SETTINGS", "HW_DESCRIPTION", "RGB_INTRINSIC_PARAMETERS", "DEPTH_INTRINSIC_PARAMETERS", "EXTRINSIC_PARAMETERS".

The "SETTINGS" section is meant for read/write parameters, meaning parameters which can be get and set by the device. A common case of setting is the image resolution in pixel. This setting will be read by the device and it'll be applied in the startup phase. If the setting fails, the device will terminate the execution with a error message.

The "HW_DESCRIPTION" section is meant for read only parameters which describe the hardware property of the device and cannot be provided by the device through software API. A common case is the 'Field Of View' property, which may or may not be supported by the physical device. When a property is present in the HW_DESCRIPTION group, the YARP RGBDSensorClient will report this value when asked for and setting will be disabled. This group can also be used to by-pass OpenNI2 API in case some functionality is not correctly working with the current device. For example the 'clipPlanes' property may return incorrect values or values using non-standard measurement unit. In this case using the HW_DESCRIPTION, a user can override the value got from OpenNI2 API with a custom value.

Note
Parameters inside the HW_DESCRIPTION are read only, so the relative set functionality will be disabled.
For parameters which are neither in SETTINGS nor in HW_DESCRIPTION groups, read / write functionality is assumed but not initial setting will be performed. Device will start with manufacturer default values.
Warning
A single parameter cannot be present into both SETTINGS and HW_DESCRIPTION groups.

The [RGB/DEPTH_INTRINSIC_PARAMETERS] group describe the camera intrinsic parameters for rgb and depth respectively.

Note
Right now only 'plumb_bob' (pinhole camera) distortion model is supported.

The [EXTRINSIC_PARAMETERS] group describe the position of the depth camera in the rgb camera frame. It is composed of a 4x4 rototranslation matrix.

Warning
: whenever more then one value is required by the setting, the values must be in parenthesys!

Parameters used by this device are:

Parameter name SubParameter Type Read / write Units Default Value Required Description Notes
SETTINGS - group Read / write - - Yes Initial setting of the device. Properties must be read/writable in order for setting to work
rgbResolution int, int Read / write pixels - Alternative to HW_DESCRIPTION Size of rgb image in pixels 2 values expected as height, width
depthResolution int, int Read / write pixels - Alternative to HW_DESCRIPTION Size of depth image in pixels Values are height, width
accuracy double Read / write meters - Alternative to HW_DESCRIPTION Accuracy of the device, as the depth measurement error at 1 meter distance
rgbFOV double, double Read / write degrees - Alternative to HW_DESCRIPTION Horizontal and Vertical fields of view of the rgb camera 2 values expected as horizontal and vertical FOVs
depthFOV double, double Read / write degrees - Alternative to HW_DESCRIPTION Horizontal and Vertical fields of view of the depth camera 2 values expected as horizontal and vertical FOVs
rgbMirroring bool Read / write true/false false Alternative to HW_DESCRIPTION Set the mirroring to the acquired rgb image
depthMirroring bool Read / write true/false false Alternative to HW_DESCRIPTION Set the mirroring to the acquired rgb image
HW_DESCRIPTION - group - - Yes Hardware description of device property. Read only property. Setting will be disabled
same as 'SETTINGS' group - Read only - - Alternative to SETTING group Parameters here are alternative to the SETTING group
RGB_INTRINSIC_PARAMETERS - group - - Yes Description of rgb camera visual parameters
focalLengthX double mm - Yes
focalLengthY double mm - Yes
principalPointX double pixel - Yes
principalPointY double pixel - Yes
distortionModel string - - Yes Reference to group of parameters describing the distortion model of the camera, example 'rgbDistortionModelGroup' This is only another group's name to be searched for in the config file
rgbDistortionModelGroup
name string - - Yes Name of the distortion model, see notes right now only 'plumb_bob' is supported
k1 double - - Yes
k2 double - - Yes
k3 double - - Yes
t1 double - - Yes
t2 double - - Yes
DEPTH_INTRINSIC_PARAMETERS - group - - Yes Description of depth camera visual parameters
focalLengthX double mm - Yes
focalLengthY double mm - Yes
principalPointX double pixel - Yes
principalPointY double pixel - Yes
distortionModel string - - Yes Reference to group of parameters describing the distortion model of the camera, example 'depthDistortionModelGroup' This is another group's name to be searched for in the config file
depthDistortionModelGroup
name string - - Yes Name of the distortion model, see notes right now only 'plumb_bob' is supported
k1 double - - Yes Radial distortion coefficient of the lens
k2 double - - Yes Radial distortion coefficient of the lens
k3 double - - Yes Radial distortion coefficient of the lens
t1 double - - Yes Tangential distortion of the lens
t2 double - - Yes Tangential distortion of the lens
EXTRINSIC_PARAMETERS - - - Yes
transformation 4x4 double matrix - - Yes trasformation matrix between depth optical frame to the rgb one

Configuration file using .ini format, using subdevice keyword.

device RGBDSensorWrapper
subdevice depthCamera
name /depthCamera
[SETTINGS]
accuracy 0.001
depthResolution (320 240) #Note the parentesys
rgbResolution (320 240)
rgbMirroring false
depthMirroring false
[HW_DESCRIPTION]
clipPlanes (0.4 4.5)
[RGB_INTRINSIC_PARAMETERS]
focalLengthX 1.0
focalLengthY 2.0
principalPointX 256.0
principalPointY 128.0
distortionModel rgb_distortion
[rgb_distortion]
name plumb_bob
k1 1.0
k2 2.0
t1 3.0
t2 4.0
k3 5.0
[DEPTH_INTRINSIC_PARAMETERS]
focalLengthX 1.0
focalLengthY 2.0
principalPointX 256.0
principalPointY 128.0
distortionModel depth_distortion
[depth_distortion]
name plumb_bob
k1 1.0
k2 2.0
t1 3.0
t2 4.0
k3 5.0
[EXTRINSIC_PARAMETERS]
transformation (1.0 0.0 0.0 0.0 0.0 1.0 0.0 0.0 0.0 0.0 1.0 0.0 0.0 0.0 0.0 1.0)

Definition at line 186 of file depthCameraDriver.h.

Member Typedef Documentation

◆ depthImage

Constructor & Destructor Documentation

◆ depthCameraDriver()

depthCameraDriver::depthCameraDriver ( )

Definition at line 92 of file depthCameraDriver.cpp.

◆ ~depthCameraDriver()

depthCameraDriver::~depthCameraDriver ( )

Definition at line 123 of file depthCameraDriver.cpp.

Member Function Documentation

◆ close()

bool depthCameraDriver::close ( void  )
virtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 595 of file depthCameraDriver.cpp.

◆ getActive()

bool depthCameraDriver::getActive ( int  feature,
bool *  isActive 
)
virtual

Get the current status of the feature, on or off.

Parameters
featurethe identifier of the feature to check
isActiveflag true if the feature is active, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1190 of file depthCameraDriver.cpp.

◆ getCameraDescription()

bool depthCameraDriver::getCameraDescription ( CameraDescriptor camera)
virtual

Get a basic description of the camera hw.

This is mainly used to determine the HW bus type in order to choose the corresponding interface for advanced controls.

Parameters
devicereturns an identifier for the bus
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1028 of file depthCameraDriver.cpp.

◆ getDepthAccuracy()

double depthCameraDriver::getDepthAccuracy ( )
virtual

Get the accuracy of the depth measure in [meter].

Returns
the accuracy of the sensor in meters.

Implements yarp::dev::IRGBDSensor.

Definition at line 817 of file depthCameraDriver.cpp.

◆ getDepthClipPlanes()

bool depthCameraDriver::getDepthClipPlanes ( double &  nearPlane,
double &  farPlane 
)
virtual

Get the clipping planes of the sensor.

Parameters
nearPlaneminimum distance at which the sensor start measuring. Object closer than this distance will not be detected.
farPlanemaximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected.
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 826 of file depthCameraDriver.cpp.

◆ getDepthFOV()

bool depthCameraDriver::getDepthFOV ( double &  horizontalFov,
double &  verticalFov 
)
virtual

Get the field of view (FOV) of the depth camera.

Parameters
horizontalFovwill return the value of the horizontal fov in degrees
verticalFovwill return the value of the vertical fov in degrees
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 799 of file depthCameraDriver.cpp.

◆ getDepthHeight()

int depthCameraDriver::getDepthHeight ( )
virtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 781 of file depthCameraDriver.cpp.

◆ getDepthImage()

bool depthCameraDriver::getDepthImage ( depthImage depthImage,
Stamp timeStamp = NULL 
)
virtual

Definition at line 885 of file depthCameraDriver.cpp.

◆ getDepthIntrinsicParam()

bool depthCameraDriver::getDepthIntrinsicParam ( Property intrinsic)
virtual

Definition at line 812 of file depthCameraDriver.cpp.

◆ getDepthMirroring()

bool depthCameraDriver::getDepthMirroring ( bool &  mirror)
virtual

Get the mirroring setting of the sensor.

Parameters
mirrortrue if image is mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IDepthVisualParams.

Definition at line 854 of file depthCameraDriver.cpp.

◆ getDepthWidth()

int depthCameraDriver::getDepthWidth ( )
virtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 790 of file depthCameraDriver.cpp.

◆ getExtrinsicParam()

bool depthCameraDriver::getExtrinsicParam ( sig::Matrix extrinsic)
virtual

Get the extrinsic parameters ofrom the device.

Parameters
extrinsicreturn a rototranslation matrix describing the position of the depth optical frame with respect to the rgb frame
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 874 of file depthCameraDriver.cpp.

◆ getFeature() [1/2]

bool depthCameraDriver::getFeature ( int  feature,
double *  value 
)
virtual

Get the current value for the requested feature.

Parameters
featurethe identifier of the feature to read
valuepointer to current value of the feature, from 0 to 1 expressed as a percentage
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1097 of file depthCameraDriver.cpp.

◆ getFeature() [2/2]

bool depthCameraDriver::getFeature ( int  feature,
double *  value1,
double *  value2 
)
virtual

Get the current value for the requested feature.

Parameters
featurethe identifier of the feaature to read
value1returns the current value of the feature, from 0 to 1 expressed as a percentage
value2returns the current value of the feature, from 0 to 1 expressed as a percentage
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1133 of file depthCameraDriver.cpp.

◆ getImages()

bool depthCameraDriver::getImages ( FlexImage colorFrame,
depthImage depthFrame,
Stamp colorStamp = NULL,
Stamp depthStamp = NULL 
)
virtual

Definition at line 988 of file depthCameraDriver.cpp.

◆ getLastErrorMsg()

ConstString depthCameraDriver::getLastErrorMsg ( Stamp timeStamp = NULL)
virtual

Definition at line 1023 of file depthCameraDriver.cpp.

◆ getMode()

bool depthCameraDriver::getMode ( int  feature,
FeatureMode mode 
)
virtual

Get the current mode for the feature.

Parameters
featurethe identifier of the feature to change
hasAutoflag true if the feature is has 'auto' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1291 of file depthCameraDriver.cpp.

◆ getRgbFOV()

bool depthCameraDriver::getRgbFOV ( double &  horizontalFov,
double &  verticalFov 
)
virtual

Get the field of view (FOV) of the rgb camera.

Parameters
horizontalFovwill return the value of the horizontal fov in degrees
verticalFovwill return the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 722 of file depthCameraDriver.cpp.

◆ getRgbHeight()

int depthCameraDriver::getRgbHeight ( )
virtual

Return the height of each frame.

Returns
rgb image height

Implements yarp::dev::IRGBDSensor.

Definition at line 604 of file depthCameraDriver.cpp.

◆ getRgbImage()

bool depthCameraDriver::getRgbImage ( FlexImage rgbImage,
Stamp timeStamp = NULL 
)
virtual

Definition at line 880 of file depthCameraDriver.cpp.

◆ getRgbIntrinsicParam()

bool depthCameraDriver::getRgbIntrinsicParam ( Property intrinsic)
virtual

Definition at line 776 of file depthCameraDriver.cpp.

◆ getRgbMirroring()

bool depthCameraDriver::getRgbMirroring ( bool &  mirror)
virtual

Get the mirroring setting of the sensor.

Parameters
mirrortrue if image is mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IRgbVisualParams.

Definition at line 735 of file depthCameraDriver.cpp.

◆ getRgbWidth()

int depthCameraDriver::getRgbWidth ( )
virtual

Return the width of each frame.

Returns
rgb image width

Implements yarp::dev::IRGBDSensor.

Definition at line 614 of file depthCameraDriver.cpp.

◆ getSensorStatus()

IRGBDSensor::RGBDSensor_status depthCameraDriver::getSensorStatus ( )
virtual

Get the surrent status of the sensor, using enum type.

Returns
an enum representing the status of the robot or an error code if any error is present

Implements yarp::dev::IRGBDSensor.

Definition at line 993 of file depthCameraDriver.cpp.

◆ hasAuto()

bool depthCameraDriver::hasAuto ( int  feature,
bool *  hasAuto 
)
virtual

Check if the requested feature has the 'auto' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'auto' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1209 of file depthCameraDriver.cpp.

◆ hasFeature()

bool depthCameraDriver::hasFeature ( int  feature,
bool *  hasFeature 
)
virtual

Check if camera has the requested feature (saturation, brightness ...

)

Parameters
featurethe identifier of the feature to check
hasFeatureflag value: true if the feature is present, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1035 of file depthCameraDriver.cpp.

◆ hasManual()

bool depthCameraDriver::hasManual ( int  feature,
bool *  hasManual 
)
virtual

Check if the requested feature has the 'manual' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'manual' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1228 of file depthCameraDriver.cpp.

◆ hasOnePush()

bool depthCameraDriver::hasOnePush ( int  feature,
bool *  hasOnePush 
)
virtual

Check if the requested feature has the 'onePush' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'onePush' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1247 of file depthCameraDriver.cpp.

◆ hasOnOff()

bool depthCameraDriver::hasOnOff ( int  feature,
bool *  HasOnOff 
)
virtual

Check if the camera has the ability to turn on/off the requested feature.

Parameters
featurethe identifier of the feature to change
hasOnOffflag true if this feature can be turned on/off, false otherwise.
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1139 of file depthCameraDriver.cpp.

◆ open()

bool depthCameraDriver::open ( yarp::os::Searchable config)
virtual

Open the DeviceDriver.

Parameters
configis a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device).
Returns
true/false upon success/failure

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 489 of file depthCameraDriver.cpp.

◆ pixFormatToCode()

int depthCameraDriver::pixFormatToCode ( openni::PixelFormat  p)
static

Definition at line 890 of file depthCameraDriver.cpp.

◆ setActive()

bool depthCameraDriver::setActive ( int  feature,
bool  onoff 
)
virtual

Set the requested feature on or off.

Parameters
featurethe identifier of the feature to change
onofftrue to activate, off to deactivate the feature
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1158 of file depthCameraDriver.cpp.

◆ setDepthAccuracy()

bool depthCameraDriver::setDepthAccuracy ( double  accuracy)
virtual

Set the accuracy of the depth measure in [meter] when possible.

Parameters
theaccuracy of the sensor in meters.
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 688 of file depthCameraDriver.cpp.

◆ setDepthClipPlanes()

bool depthCameraDriver::setDepthClipPlanes ( double  nearPlane,
double  farPlane 
)
virtual

Set the clipping planes of the sensor.

Parameters
nearPlaneminimum distance at which the sensor start measuring. Object closer than this distance will not be detected.
farPlanemaximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected.
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 841 of file depthCameraDriver.cpp.

◆ setDepthFOV()

bool depthCameraDriver::setDepthFOV ( double  horizontalFov,
double  verticalFov 
)
virtual

Set the field of view (FOV) of the depth camera.

Parameters
horizontalFovwill set the value of the horizontal fov in degrees
verticalFovwill set the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 679 of file depthCameraDriver.cpp.

◆ setDepthMirroring()

bool depthCameraDriver::setDepthMirroring ( bool  mirror)
virtual

Set the mirroring setting of the sensor.

Parameters
mirrortrue if image should be mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IDepthVisualParams.

Definition at line 864 of file depthCameraDriver.cpp.

◆ setDepthResolution()

bool depthCameraDriver::setDepthResolution ( int  width,
int  height 
)
virtual

Set the resolution of the depth image from the camera.

Parameters
widthimage width
heightimage height
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 624 of file depthCameraDriver.cpp.

◆ setFeature() [1/2]

bool depthCameraDriver::setFeature ( int  feature,
double  value 
)
virtual

Set the requested feature to a value (saturation, brightness ...

)

Parameters
featurethe identifier of the feature to change
valuenew value of the feature, range from 0 to 1 expressed as a percentage
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1056 of file depthCameraDriver.cpp.

◆ setFeature() [2/2]

bool depthCameraDriver::setFeature ( int  feature,
double  value1,
double  value2 
)
virtual

Set the requested feature to a value using 2 params (like white balance)

Parameters
featurethe identifier of the feature to change
value1first param, from 0 to 1 expressed as a percentage
value2second param, from 0 to 1 expressed as a percentage
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1127 of file depthCameraDriver.cpp.

◆ setMode()

bool depthCameraDriver::setMode ( int  feature,
FeatureMode  mode 
)
virtual

Set the requested mode for the feature.

Parameters
featurethe identifier of the feature to change
auto_onofftrue to activate 'auto' mode, false to activate 'manual' mode
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1259 of file depthCameraDriver.cpp.

◆ setOnePush()

bool depthCameraDriver::setOnePush ( int  feature)
virtual

Set the requested feature to a value (saturation, brightness ...

)

Parameters
featurethe identifier of the feature to change
valuenew value of the feature, from 0 to 1 as a percentage of param range
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls2.

Definition at line 1311 of file depthCameraDriver.cpp.

◆ setRgbFOV()

bool depthCameraDriver::setRgbFOV ( double  horizontalFov,
double  verticalFov 
)
virtual

Set the field of view (FOV) of the rgb camera.

Parameters
horizontalFovwill set the value of the horizontal fov in degrees
verticalFovwill set the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 670 of file depthCameraDriver.cpp.

◆ setRgbMirroring()

bool depthCameraDriver::setRgbMirroring ( bool  mirror)
virtual

Set the mirroring setting of the sensor.

Parameters
mirrortrue if image should be mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IRgbVisualParams.

Definition at line 746 of file depthCameraDriver.cpp.

◆ setRgbResolution()

bool depthCameraDriver::setRgbResolution ( int  width,
int  height 
)
virtual

Set the resolution of the rgb image from the camera.

Parameters
widthimage width
heightimage height
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 654 of file depthCameraDriver.cpp.


The documentation for this class was generated from the following files: