YARP
Yet Another Robot Platform
depthCameraDriver.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #ifndef DEPTHCAMERA_DRIVER_H
20 #define DEPTHCAMERA_DRIVER_H
21 
22 #include <string>
23 #include <map>
24 
25 #include <yarp/dev/DeviceDriver.h>
27 #include <yarp/os/PeriodicThread.h>
28 #include <yarp/sig/all.h>
29 #include <yarp/sig/Matrix.h>
30 #include <yarp/os/Stamp.h>
31 #include <yarp/dev/IRGBDSensor.h>
33 #include <OpenNI.h>
34 
35 
36 #ifndef RAD2DEG
37 #define RAD2DEG (180/3.14159265359)
38 #endif
39 
40 #ifndef DEG2RAD
41 #define DEG2RAD (3.14159265359/180.0)
42 #endif
43 
45 
195  public yarp::dev::IRGBDSensor,
197 {
198 private:
200  typedef yarp::os::Stamp Stamp;
203 
204 public:
207  static int pixFormatToCode(openni::PixelFormat p);
208 
209  // DeviceDriver
210  bool open(yarp::os::Searchable& config) override;
211  bool close() override;
212 
213  // IRGBDSensor
214  int getRgbHeight() override;
215  int getRgbWidth() override;
217  bool getRgbResolution(int& width, int& height) override;
218  bool setRgbResolution(int width, int height) override;
219  bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
220  bool setRgbFOV(double horizontalFov, double verticalFov) override;
221  bool getRgbMirroring(bool& mirror) override;
222  bool setRgbMirroring(bool mirror) override;
223 
224  bool getRgbIntrinsicParam(Property& intrinsic) override;
225  int getDepthHeight() override;
226  int getDepthWidth() override;
227  bool setDepthResolution(int width, int height) override;
228  bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
229  bool setDepthFOV(double horizontalFov, double verticalFov) override;
230  bool getDepthIntrinsicParam(Property& intrinsic) override;
231  double getDepthAccuracy() override;
232  bool setDepthAccuracy(double accuracy) override;
233  bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
234  bool setDepthClipPlanes(double nearPlane, double farPlane) override;
235  bool getDepthMirroring(bool& mirror) override;
236  bool setDepthMirroring(bool mirror) override;
237 
238 
239  bool getExtrinsicParam(yarp::sig::Matrix& extrinsic) override;
240  bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = NULL) override;
241  bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = NULL) override;
242  bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp=NULL, Stamp* depthStamp=NULL) override;
243 
245  std::string getLastErrorMsg(Stamp* timeStamp = NULL) override;
246 
247  //IFrameGrabberControls
248  bool getCameraDescription(CameraDescriptor *camera) override;
249  bool hasFeature(int feature, bool* hasFeature) 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;
257  bool hasAuto( int feature, bool* hasAuto) override;
258  bool hasManual( int feature, bool* hasManual) override;
259  bool hasOnePush(int feature, bool* hasOnePush) override;
260  bool setMode( int feature, FeatureMode mode) override;
261  bool getMode( int feature, FeatureMode *mode) override;
262  bool setOnePush(int feature) override;
263 
264 private:
265  //method
266  inline bool initializeOpeNIDevice();
267  inline bool setParams();
268  bool getImage(FlexImage& Frame, Stamp* Stamp, streamFrameListener *sourceFrame);
269  bool getImage(depthImage& Frame, Stamp* Stamp, streamFrameListener *sourceFrame);
270  bool setResolution(int w, int h, openni::VideoStream& stream);
271  bool setFOV(double horizontalFov, double verticalFov, openni::VideoStream& stream);
272  bool setIntrinsic(yarp::os::Property& intrinsic, const yarp::sig::IntrinsicParams& values);
273  void settingErrorMsg(const std::string& error, bool& ret);
274 
275  //properties
276  openni::VideoStream m_depthStream;
277  openni::VideoStream m_imageStream;
278  openni::Device m_device;
279  streamFrameListener* m_depthFrame;
280  streamFrameListener* m_imageFrame;
281  std::string m_lastError;
282  yarp::dev::RGBDSensorParamParser* m_paramParser;
283  bool m_depthRegistration;
284  std::vector<cameraFeature_id_t> m_supportedFeatures;
285 };
286 #endif
define common interfaces to discover remote camera capabilities
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.
Definition: DeviceDriver.h:38
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:56
The RGBDSensorParamParser class.
A class for storing options and configuration information.
Definition: Property.h:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
Image class with user control of representation details.
Definition: Image.h:403
A class for a Matrix.
Definition: Matrix.h:46
constexpr char accuracy[]
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).