YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
depthCameraDriver.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: LGPL-2.1-or-later
4 */
5
6#ifndef DEPTHCAMERA_DRIVER_H
7#define DEPTHCAMERA_DRIVER_H
8
9#include <string>
10#include <map>
11
15#include <yarp/sig/all.h>
16#include <yarp/sig/Matrix.h>
17#include <yarp/os/Stamp.h>
20#include <OpenNI.h>
21
22
23#ifndef RAD2DEG
24#define RAD2DEG (180/3.14159265359)
25#endif
26
27#ifndef DEG2RAD
28#define DEG2RAD (3.14159265359/180.0)
29#endif
30
32
184{
185private:
187 typedef yarp::os::Stamp Stamp;
190
191public:
194 static int pixFormatToCode(openni::PixelFormat p);
195
196 // DeviceDriver
197 bool open(yarp::os::Searchable& config) override;
198 bool close() override;
199
200 // IRGBDSensor
201 int getRgbHeight() override;
202 int getRgbWidth() override;
204 bool getRgbResolution(int& width, int& height) override;
205 bool setRgbResolution(int width, int height) override;
206 bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
207 bool setRgbFOV(double horizontalFov, double verticalFov) override;
208 bool getRgbMirroring(bool& mirror) override;
209 bool setRgbMirroring(bool mirror) override;
210
211 bool getRgbIntrinsicParam(Property& intrinsic) override;
212 int getDepthHeight() override;
213 int getDepthWidth() override;
214 bool setDepthResolution(int width, int height) override;
215 bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
216 bool setDepthFOV(double horizontalFov, double verticalFov) override;
217 bool getDepthIntrinsicParam(Property& intrinsic) override;
218 double getDepthAccuracy() override;
219 bool setDepthAccuracy(double accuracy) override;
220 bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
221 bool setDepthClipPlanes(double nearPlane, double farPlane) override;
222 bool getDepthMirroring(bool& mirror) override;
223 bool setDepthMirroring(bool mirror) override;
224
225
226 bool getExtrinsicParam(yarp::sig::Matrix& extrinsic) override;
227 bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = NULL) override;
228 bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = NULL) override;
229 bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp=NULL, Stamp* depthStamp=NULL) override;
230
232 std::string getLastErrorMsg(Stamp* timeStamp = NULL) override;
233
234 //IFrameGrabberControls
235 bool getCameraDescription(CameraDescriptor *camera) override;
236 bool hasFeature(int feature, bool* hasFeature) override;
237 bool setFeature(int feature, double value) override;
238 bool getFeature(int feature, double* value) override;
239 bool setFeature(int feature, double value1, double value2) override;
240 bool getFeature(int feature, double* value1, double* value2) override;
241 bool hasOnOff( int feature, bool* HasOnOff) override;
242 bool setActive( int feature, bool onoff) override;
243 bool getActive( int feature, bool* isActive) override;
244 bool hasAuto( int feature, bool* hasAuto) override;
245 bool hasManual( int feature, bool* hasManual) override;
246 bool hasOnePush(int feature, bool* hasOnePush) override;
247 bool setMode( int feature, FeatureMode mode) override;
248 bool getMode( int feature, FeatureMode *mode) override;
249 bool setOnePush(int feature) override;
250
251private:
252 //method
253 inline bool initializeOpeNIDevice();
254 inline bool setParams();
255 bool getImage(FlexImage& Frame, Stamp* Stamp, streamFrameListener *sourceFrame);
256 bool getImage(depthImage& Frame, Stamp* Stamp, streamFrameListener *sourceFrame);
257 bool setResolution(int w, int h, openni::VideoStream& stream);
258 bool setFOV(double horizontalFov, double verticalFov, openni::VideoStream& stream);
259 bool setIntrinsic(yarp::os::Property& intrinsic, const yarp::sig::IntrinsicParams& values);
260 void settingErrorMsg(const std::string& error, bool& ret);
261
262 //properties
263 openni::VideoStream m_depthStream;
264 openni::VideoStream m_imageStream;
265 openni::Device m_device;
266 streamFrameListener* m_depthFrame;
267 streamFrameListener* m_imageFrame;
268 std::string m_lastError;
270 bool m_depthRegistration;
271 std::vector<cameraFeature_id_t> m_supportedFeatures;
272};
273#endif
bool ret
contains the definition of a Matrix type
depthCamera: YARP driver for OpenNI2 compatible devices.
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
int getDepthHeight() override
Return the height of each frame.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
int getRgbHeight() override
Return the height of each frame.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool close() override
Close the DeviceDriver.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ... )
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
int getRgbWidth() override
Return the width of each frame.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
int getDepthWidth() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ... )
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
static int pixFormatToCode(openni::PixelFormat p)
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ... )
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
Interface implemented by all device drivers.
Control interface for frame grabber devices.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition IRGBDSensor.h:39
The RGBDSensorParamParser class.
A class for storing options and configuration information.
Definition Property.h:33
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
Image class with user control of representation details.
Definition Image.h:363
Typed image class.
Definition Image.h:605
A class for a Matrix.
Definition Matrix.h:39
constexpr char accuracy[]
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).