Main MRPT website > C++ reference for MRPT 1.4.0
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-2016, 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 
31  public:
32 
33  COpenNI2Generic(); //!< Default ctor
34  ~COpenNI2Generic(); //!< Default ctor
35 
36  /** Get a list of the connected OpenNI2 sensors.
37  */
39 
40  /** Kill the OpenNI2 driver
41  */
42  void kill();
43 
44  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
45  * \param out_img The output retrieved RGB image (only if there_is_obs=true).
46  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
47  * \param there_is_obs If set to false, there was no new observation.
48  * \param hardware_error True on hardware/comms error.
49  * \param sensor_id The index of the sensor accessed.
50  *
51  */
53  mrpt::utils::CImage &rgb_img,
54  uint64_t &timestamp,
55  bool &there_is_obs,
56  bool &hardware_error ,
57  unsigned sensor_id = 0);
58 
59  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
60  * \param depth_img The output retrieved depth image (only if there_is_obs=true).
61  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
62  * \param there_is_obs If set to false, there was no new observation.
63  * \param hardware_error True on hardware/comms error.
64  * \param sensor_id The index of the sensor accessed.
65  *
66  */
68  mrpt::math::CMatrix &depth_img,
69  uint64_t &timestamp,
70  bool &there_is_obs,
71  bool &hardware_error ,
72  unsigned sensor_id = 0);
73 
74  /** The main data retrieving function, to be called after calling loadConfig() and initialize().
75  * \param out_obs The output retrieved observation (only if there_is_obs=true).
76  * \param there_is_obs If set to false, there was no new observation.
77  * \param hardware_error True on hardware/comms error.
78  * \param sensor_id The index of the sensor accessed.
79  *
80  * \sa doProcess
81  */
84  bool &there_is_obs,
85  bool &hardware_error ,
86  unsigned sensor_id = 0);
87 
88  /** @name Sensor parameters (alternative to \a loadConfig ) and manual control
89  @{ */
90 
91 
92  /** 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.
93  * Raises an exception upon error.
94  * \exception std::exception A textual description of the error.
95  */
96  void open(unsigned sensor_id = 0);
97 
98  /** Open a set of RGBD devices specified by their serial number. Raises an exception when the demanded serial numbers
99  * are not among the connected devices. This function also fills a vector with the serial numbers of the connected
100  * OpenNI2 sensors (this requires openning the sensors which are still closed to read their serial)
101  */
102  unsigned int openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired);
103 
104  /** Open a RGBD device specified by its serial number. This method is a wrapper for
105  * openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired)
106  * This method requires to open the sensors which are still closed to read their serial.
107  */
108  unsigned int openDeviceBySerial(const unsigned int SerialRequired);
109 
110  /** Get the ID of the device corresponding to 'SerialRequired'.
111  */
112  bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int& sensor_id) const;
113 
114  /** Check if the given 'sensor_id' has been open.*/
115  bool isOpen(const unsigned sensor_id) const; //!< Whether there is a working connection to the sensor
116 
117  /** Close the conection to the sensor (not need to call it manually unless desired for some reason,
118  * since it's called at destructor) */
119  void close(unsigned sensor_id = 0);
120 
121  /** The amount of available devices at initialization */
122  int getNumDevices()const;
123 
124  /** @} */
125  void setVerbose(bool verbose);
126  bool isVerbose() const;
127 
128  protected:
129 
130  /** The list of available devices */
131  class CDevice;
132  static std::vector<stlplus::smart_ptr<CDevice> > vDevices;
133  static int numInstances;
134 
135  /** A vector with the serial numbers of the available devices */
136  std::vector<int> vSerialNums;
137 
138  /** The same options (width, height and fps) are set for all the sensors. (This could be changed if necessary) */
139  int m_width, m_height;
140  float m_fps;
141  int m_rgb_format, m_depth_format;
142  bool m_verbose;
143  bool getColorSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
144  bool getDepthSensorParam(mrpt::utils::TCamera& param, unsigned sensor_id = 0) const;
145  void showLog(const std::string& message)const;
146 
147  /** The data that the RGBD sensors can return */
148  bool m_grab_image, m_grab_depth, m_grab_3D_points ; //!< Default: all true
149 
150  }; // End of class
151 
152  } // End of NS
153 
154 } // End of NS
155 
156 #endif
An abstract class for accessing OpenNI2 compatible sensors.
bool getColorSensorParam(mrpt::utils::TCamera &param, unsigned sensor_id=0) const
unsigned int openDeviceBySerial(const unsigned int SerialRequired)
Open a RGBD device specified by its serial number.
void getNextFrameD(mrpt::math::CMatrix &depth_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
void showLog(const std::string &message) const
int getConnectedDevices()
Get a list of the connected OpenNI2 sensors.
void getNextFrameRGB(mrpt::utils::CImage &rgb_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
bool isOpen(const unsigned sensor_id) const
Check if the given 'sensor_id' has been open.
void getNextFrameRGBD(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int &sensor_id) const
Get the ID of the device corresponding to 'SerialRequired'.
static std::vector< stlplus::smart_ptr< CDevice > > vDevices
std::vector< int > vSerialNums
A vector with the serial numbers of the available devices.
void open(unsigned sensor_id=0)
Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - us...
int getNumDevices() const
The amount of available devices at initialization.
void close(unsigned sensor_id=0)
Close the conection to the sensor (not need to call it manually unless desired for some reason,...
void kill()
Kill the OpenNI2 driver.
bool m_grab_3D_points
Default: all true.
unsigned int openDevicesBySerialNum(const std::set< unsigned > &vSerialRequired)
Open a set of RGBD devices specified by their serial number.
bool getDepthSensorParam(mrpt::utils::TCamera &param, unsigned sensor_id=0) const
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:31
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:102
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:32
#define HWDRIVERS_IMPEXP
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.



Page generated by Doxygen 1.9.1 for MRPT 1.4.0 SVN: at Mon Apr 18 04:08:57 UTC 2022