A generic interface for cameras that have both color camera as well as depth camera sensor, like kinect device. More...
#include <yarp/dev/IRGBDSensor.h>
Public Types | |
enum | RGBDSensor_status { RGBD_SENSOR_NOT_READY = 0 , RGBD_SENSOR_OK_STANDBY = 1 , RGBD_SENSOR_OK_IN_USE = 2 , RGB_SENSOR_ERROR = 3 , DEPTH_SENSOR_ERROR = 4 , RGBD_SENSOR_GENERIC_ERROR = 5 , RGBD_SENSOR_TIMEOUT = 6 } |
Public Member Functions | |
virtual | ~IRGBDSensor () |
virtual yarp::dev::ReturnValue | getExtrinsicParam (yarp::sig::Matrix &extrinsic)=0 |
Get the extrinsic parameters from the device. | |
virtual yarp::dev::ReturnValue | getLastErrorMsg (std::string &message, yarp::os::Stamp *timeStamp=nullptr)=0 |
Return an error message in case of error. | |
virtual yarp::dev::ReturnValue | getRgbImage (yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr)=0 |
Get the rgb frame from the device. | |
virtual yarp::dev::ReturnValue | getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=0 |
Get the depth frame from the device. | |
virtual yarp::dev::ReturnValue | 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. | |
virtual yarp::dev::ReturnValue | getSensorStatus (RGBDSensor_status &status)=0 |
Get the current status of the sensor, using enum type. | |
![]() | |
virtual | ~IRgbVisualParams () |
virtual int | getRgbHeight ()=0 |
Return the height of each frame. | |
virtual int | getRgbWidth ()=0 |
Return the width of each frame. | |
virtual yarp::dev::ReturnValue | getRgbSupportedConfigurations (std::vector< yarp::dev::CameraConfig > &configurations)=0 |
Get the possible configurations of the camera. | |
virtual yarp::dev::ReturnValue | getRgbResolution (int &width, int &height)=0 |
Get the resolution of the rgb image from the camera. | |
virtual yarp::dev::ReturnValue | setRgbResolution (int width, int height)=0 |
Set the resolution of the rgb image from the camera. | |
virtual yarp::dev::ReturnValue | getRgbFOV (double &horizontalFov, double &verticalFov)=0 |
Get the field of view (FOV) of the rgb camera. | |
virtual yarp::dev::ReturnValue | setRgbFOV (double horizontalFov, double verticalFov)=0 |
Set the field of view (FOV) of the rgb camera. | |
virtual yarp::dev::ReturnValue | getRgbIntrinsicParam (yarp::os::Property &intrinsic)=0 |
Get the intrinsic parameters of the rgb camera. | |
virtual yarp::dev::ReturnValue | getRgbMirroring (bool &mirror)=0 |
Get the mirroring setting of the sensor. | |
virtual yarp::dev::ReturnValue | setRgbMirroring (bool mirror)=0 |
Set the mirroring setting of the sensor. | |
![]() | |
virtual | ~IDepthVisualParams () |
virtual int | getDepthHeight ()=0 |
Return the height of each frame. | |
virtual int | getDepthWidth ()=0 |
Return the height of each frame. | |
virtual yarp::dev::ReturnValue | getDepthResolution (int &width, int &height)=0 |
Get the resolution of the depth image from the camera. | |
virtual yarp::dev::ReturnValue | setDepthResolution (int width, int height)=0 |
Set the resolution of the depth image from the camera. | |
virtual yarp::dev::ReturnValue | getDepthFOV (double &horizontalFov, double &verticalFov)=0 |
Get the field of view (FOV) of the depth camera. | |
virtual yarp::dev::ReturnValue | setDepthFOV (double horizontalFov, double verticalFov)=0 |
Set the field of view (FOV) of the depth camera. | |
virtual yarp::dev::ReturnValue | getDepthIntrinsicParam (yarp::os::Property &intrinsic)=0 |
Get the intrinsic parameters of the depth camera. | |
virtual yarp::dev::ReturnValue | getDepthAccuracy (double &accuracy)=0 |
Get the minimum detectable variation in distance [meter]. | |
virtual yarp::dev::ReturnValue | setDepthAccuracy (double accuracy)=0 |
Set the minimum detectable variation in distance [meter] when possible. | |
virtual yarp::dev::ReturnValue | getDepthClipPlanes (double &nearPlane, double &farPlane)=0 |
Get the clipping planes of the sensor. | |
virtual yarp::dev::ReturnValue | setDepthClipPlanes (double nearPlane, double farPlane)=0 |
Set the clipping planes of the sensor. | |
virtual yarp::dev::ReturnValue | getDepthMirroring (bool &mirror)=0 |
Get the mirroring setting of the sensor. | |
virtual yarp::dev::ReturnValue | setDepthMirroring (bool mirror)=0 |
Set the mirroring setting of the sensor. | |
A generic interface for cameras that have both color camera as well as depth camera sensor, like kinect device.
This interface uses the existing IRgbVisualParams and IDepthVisualParams interfaces to retrieve the information about the cameras. This device extends the functionality by adding methods for getting extrinsic parameters and to actually retrieve the images. The images can be synchronized on client side by using the PortSynchronizer object. How the synch policy is implemented depends on the client device, custom policy can be used.
Definition at line 36 of file IRGBDSensor.h.
Enumerator | |
---|---|
RGBD_SENSOR_NOT_READY | |
RGBD_SENSOR_OK_STANDBY | |
RGBD_SENSOR_OK_IN_USE | |
RGB_SENSOR_ERROR | |
DEPTH_SENSOR_ERROR | |
RGBD_SENSOR_GENERIC_ERROR | |
RGBD_SENSOR_TIMEOUT |
Definition at line 45 of file IRGBDSensor.h.
|
virtualdefault |
|
pure virtual |
Get the depth frame from the device.
depthImage | the depth image to be filled, depth measured in meters. |
timeStamp | time in which the image was acquired. Optional, ignored if nullptr. |
Implemented in RGBDSensor_nwc_yarp.
|
pure virtual |
Get the extrinsic parameters from the device.
extrinsic | return a rototranslation matrix describing the position of the depth optical frame with respect to the rgb frame |
Implemented in realsense2Driver, RgbdSensor_nwc_ros2, FakeDepthCameraDriver_mini, RGBDSensor_nwc_yarp, and depthCameraDriver.
|
pure virtual |
Get the both the color and depth frame in a single call.
Implementation should assure the best possible synchronization is achieved accordingly to synch policy set by the user. TimeStamps are referred to acquisition time of the corresponding piece of information. If the device is not providing TimeStamps, then 'timeStamp' field should be set to '-1'.
colorFrame | pointer to FlexImage data to hold the color frame from the sensor |
depthFrame | pointer to FlexImage data to hold the depth frame from the sensor |
colorStamp | pointer to memory to hold the Stamp of the color frame |
depthStamp | pointer to memory to hold the Stamp of the depth frame |
Implemented in RGBDSensor_nwc_yarp.
|
pure virtual |
Return an error message in case of error.
For debugging purpose and user notification. Error message will be reset after any successful command
message | A string explaining the last error occurred. |
Implemented in FakeDepthCameraDriver_mini, and RGBDSensor_nwc_yarp.
|
pure virtual |
Get the rgb frame from the device.
The pixel type of the source image will usually be set as a VOCAB_PIXEL_RGB, but the user can call the function with the pixel type of his/her choice. The conversion if possible, will be done automatically on client side (TO BO VERIFIED). Note: this will consume CPU power because it will not use GPU optimization. Use VOCAB_PIXEL_RGB for best performances.
rgbImage | the image to be filled. |
timeStamp | time in which the image was acquired. Optional, ignored if nullptr. |
Implemented in depthCameraDriver, realsense2Driver, FakeDepthCameraDriver_mini, RgbdSensor_nwc_ros2, and RGBDSensor_nwc_yarp.
|
pure virtual |
Get the current status of the sensor, using enum type.
status | an enum representing the status of the robot or an error code if any error is present |