Main MRPT website > C++ reference for MRPT 1.5.5
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  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
37  * \param out_img The output retrieved RGB image (only if there_is_obs=true).
38  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
39  * \param there_is_obs If set to false, there was no new observation.
40  * \param hardware_error True on hardware/comms error.
41  * \param sensor_id The index of the sensor accessed. */
42  void getNextFrameRGB(
43  mrpt::utils::CImage &rgb_img,
44  uint64_t &timestamp,
45  bool &there_is_obs,
46  bool &hardware_error ,
47  unsigned sensor_id = 0);
48 
49  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
50  * \param depth_img The output retrieved depth image (only if there_is_obs=true).
51  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
52  * \param there_is_obs If set to false, there was no new observation.
53  * \param hardware_error True on hardware/comms error.
54  * \param sensor_id The index of the sensor accessed. */
55  void getNextFrameD(
56  mrpt::math::CMatrix &depth_img,
57  uint64_t &timestamp,
58  bool &there_is_obs,
59  bool &hardware_error ,
60  unsigned sensor_id = 0);
61 
62  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
63  * \param out_obs The output retrieved observation (only if there_is_obs=true).
64  * \param there_is_obs If set to false, there was no new observation.
65  * \param hardware_error True on hardware/comms error.
66  * \param sensor_id The index of the sensor accessed.
67  *
68  * \sa doProcess
69  */
70  void getNextFrameRGBD(
72  bool &there_is_obs,
73  bool &hardware_error ,
74  unsigned sensor_id = 0);
75 
76  /** @name Open/Close device methods
77  @{ */
78  /** 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.
79  * Raises an exception upon error.
80  * \exception std::exception A textual description of the error.
81  */
82  void open(unsigned sensor_id = 0);
83 
84  /** Open a set of RGBD devices specified by their serial number. Raises an exception when the demanded serial numbers
85  * are not among the connected devices. This function also fills a vector with the serial numbers of the connected
86  * OpenNI2 sensors (this requires openning the sensors which are still closed to read their serial)
87  */
88  unsigned int openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired);
89 
90  /** Open a RGBD device specified by its serial number. This method is a wrapper for
91  * openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired)
92  * This method requires to open the sensors which are still closed to read their serial.
93  */
94  unsigned int openDeviceBySerial(const unsigned int SerialRequired);
95 
96  bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int& sensor_id) const; //!< Get the ID of the device corresponding to 'SerialRequired'.
97  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
98  void kill(); //!< Kill the OpenNI2 driver \sa start()
99  bool isOpen(const unsigned sensor_id) const; //!< Whether there is a working connection to the sensor
100  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
101  int getNumDevices()const; //!< The number of available devices at initialization
102  int getConnectedDevices(); //!< Get a list of the connected OpenNI2 sensors.
103 
104  /** @} */
105 
106  void setVerbose(bool verbose);
107  bool isVerbose() const;
108 
109  bool getColorSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
110  bool getDepthSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
111 
112  protected:
113 
114  /** The list of available devices */
116  static std::vector<stlplus::smart_ptr<CDevice> > vDevices;
117  static int numInstances;
118 
119  /** A vector with the serial numbers of the available devices */
120  std::vector<int> vSerialNums;
121 
122  /** The same options (width, height and fps) are set for all the sensors. (This could be changed if necessary) */
123  int m_width, m_height;
124  float m_fps;
125  int m_rgb_format, m_depth_format;
126  bool m_verbose;
127  void showLog(const std::string& message)const;
128  /** The data that the RGBD sensors can return */
129  bool m_grab_image, m_grab_depth, m_grab_3D_points ; //!< Default: all true
130  }; // End of class
131  } // End of NS
132 } // End of NS
133 #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.
static std::vector< stlplus::smart_ptr< CDevice > > vDevices
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.5 Git: e06b63dbf Fri Dec 1 14:41:11 2017 +0100 at lun oct 28 01:31:35 CET 2019