Main MRPT website > C++ reference for MRPT 1.5.7
COpenNI2Generic.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef mrpt_COpenNI2Generic_H
10 #define mrpt_COpenNI2Generic_H
11 
13 
15 
16 
17 namespace mrpt
18 {
19  namespace hwdrivers
20  {
21  /** An abstract class for accessing OpenNI2 compatible sensors.
22  * This class permits to access several sensors simultaneously. The same options (resolution, fps, etc.) are used for every sensor.
23  *
24  * More references to read:
25  * - http://http://www.openni.org/
26  * \ingroup mrpt_hwdrivers_grp
27  */
29  {
30  public:
31  COpenNI2Generic(); //!< Default ctor (width=640, height=480, fps=30)
32  COpenNI2Generic(int width, int height, float fps = 30.0f, bool open_streams_now = true); //!< Ctor. \sa start()
33 
34  ~COpenNI2Generic(); //!< Default ctor
35 
36  /**Get the number of OpenNI2 cameras currently open via COpenNI2Generic*/
37  static int getNumInstances();
38 
39  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
40  * \param out_img The output retrieved RGB image (only if there_is_obs=true).
41  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
42  * \param there_is_obs If set to false, there was no new observation.
43  * \param hardware_error True on hardware/comms error.
44  * \param sensor_id The index of the sensor accessed. */
45  void getNextFrameRGB(
46  mrpt::utils::CImage &rgb_img,
47  uint64_t &timestamp,
48  bool &there_is_obs,
49  bool &hardware_error ,
50  unsigned sensor_id = 0);
51 
52  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
53  * \param depth_img The output retrieved depth image (only if there_is_obs=true).
54  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
55  * \param there_is_obs If set to false, there was no new observation.
56  * \param hardware_error True on hardware/comms error.
57  * \param sensor_id The index of the sensor accessed. */
58  void getNextFrameD(
59  mrpt::math::CMatrix &depth_img,
60  uint64_t &timestamp,
61  bool &there_is_obs,
62  bool &hardware_error ,
63  unsigned sensor_id = 0);
64 
65  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
66  * \param out_obs The output retrieved observation (only if there_is_obs=true).
67  * \param there_is_obs If set to false, there was no new observation.
68  * \param hardware_error True on hardware/comms error.
69  * \param sensor_id The index of the sensor accessed.
70  *
71  * \sa doProcess
72  */
73  void getNextFrameRGBD(
75  bool &there_is_obs,
76  bool &hardware_error ,
77  unsigned sensor_id = 0);
78 
79  /** @name Open/Close device methods
80  @{ */
81  /** Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - users may also call initialize(), which in turn calls this method.
82  * Raises an exception upon error.
83  * \exception std::exception A textual description of the error.
84  */
85  void open(unsigned sensor_id = 0);
86 
87  /** Open a set of RGBD devices specified by their serial number. Raises an exception when the demanded serial numbers
88  * are not among the connected devices. This function also fills a vector with the serial numbers of the connected
89  * OpenNI2 sensors (this requires openning the sensors which are still closed to read their serial)
90  */
91  unsigned int openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired);
92 
93  /** Open a RGBD device specified by its serial number. This method is a wrapper for
94  * openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired)
95  * This method requires to open the sensors which are still closed to read their serial.
96  */
97  unsigned int openDeviceBySerial(const unsigned int SerialRequired);
98 
99  bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int& sensor_id) const; //!< Get the ID of the device corresponding to 'SerialRequired'.
100  bool start(); //!< Open all sensor streams (normally called automatically at constructor, no need to call it manually). \return false on error \sa kill() to close
101  void kill(); //!< Kill the OpenNI2 driver \sa start()
102  bool isOpen(const unsigned sensor_id) const; //!< Whether there is a working connection to the sensor
103  void close(unsigned sensor_id = 0); //!< Close the connection to the sensor (no need to call it manually unless desired for some reason, since it's called at destructor
104  int getNumDevices()const; //!< The number of available devices at initialization
105  int getConnectedDevices(); //!< Get a list of the connected OpenNI2 sensors.
106 
107  /** @} */
108 
109  void setVerbose(bool verbose);
110  bool isVerbose() const;
111 
112  bool getColorSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
113  bool getDepthSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
114 
116  protected:
117  /** A vector with the serial numbers of the available devices */
118  std::vector<int> vSerialNums;
119 
120  /** The same options (width, height and fps) are set for all the sensors. (This could be changed if necessary) */
121  int m_width, m_height;
122  float m_fps;
123  int m_rgb_format, m_depth_format;
124  bool m_verbose;
125  void showLog(const std::string& message)const;
126  /** The data that the RGBD sensors can return */
127  bool m_grab_image, m_grab_depth, m_grab_3D_points ; //!< Default: all true
128  }; // End of class
129  } // End of NS
130 } // End of NS
131 #endif
bool m_grab_image
The data that the RGBD sensors can return.
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:101
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
GLenum GLsizei width
Definition: glext.h:3513
int m_width
The same options (width, height and fps) are set for all the sensors.
An abstract class for accessing OpenNI2 compatible sensors.
std::vector< int > vSerialNums
A vector with the serial numbers of the available devices.
GLsizei const GLchar ** string
Definition: glext.h:3919
unsigned __int64 uint64_t
Definition: rptypes.h:52
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
GLuint start
Definition: glext.h:3512
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:30
GLenum GLsizei GLsizei height
Definition: glext.h:3523
GLfloat param
Definition: glext.h:3705
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:31



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019