MRPT  1.9.9
COpenNI2Generic.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
12 
13 namespace mrpt::hwdrivers
14 {
15 /** An abstract class for accessing OpenNI2 compatible sensors.
16  * This class permits to access several sensors simultaneously. The same
17  *options (resolution, fps, etc.) are used for every sensor.
18  *
19  * More references to read:
20  * - http://http://www.openni.org/
21  * \ingroup mrpt_hwdrivers_grp
22  */
24 {
25  public:
26  /** Default ctor (width=640, height=480, fps=30)
27  */
29  /** Ctor. \sa start()
30  */
32  int width, int height, float fps = 30.0f, bool open_streams_now = true);
33 
34  /** Default ctor
35  */
37 
38  /**Get the number of OpenNI2 cameras currently open via COpenNI2Generic*/
39  static int getNumInstances();
40 
41  /** The main data retrieving function, to be called after calling
42  * loadConfig() and initialize().
43  * \param out_img The output retrieved RGB image (only if
44  * there_is_obs=true).
45  * \param timestamp The timestamp of the capture (only if
46  * 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  void getNextFrameRGB(
51  mrpt::img::CImage& rgb_img, mrpt::system::TTimeStamp& timestamp,
52  bool& there_is_obs, bool& hardware_error, unsigned sensor_id = 0);
53 
54  /** The main data retrieving function, to be called after calling
55  * loadConfig() and initialize().
56  * \param depth_img The output retrieved depth image (only if
57  * there_is_obs=true).
58  * \param timestamp The timestamp of the capture (only if
59  * there_is_obs=true).
60  * \param there_is_obs If set to false, there was no new observation.
61  * \param hardware_error True on hardware/comms error.
62  * \param sensor_id The index of the sensor accessed. */
63  void getNextFrameD(
64  mrpt::math::CMatrix_u16& depth_img_mm,
65  mrpt::system::TTimeStamp& timestamp, bool& there_is_obs,
66  bool& hardware_error, unsigned sensor_id = 0);
67 
68  /** The main data retrieving function, to be called after calling
69  * loadConfig() and initialize().
70  * \param out_obs The output retrieved observation (only if
71  * there_is_obs=true).
72  * \param there_is_obs If set to false, there was no new observation.
73  * \param hardware_error True on hardware/comms error.
74  * \param sensor_id The index of the sensor accessed.
75  *
76  * \sa doProcess
77  */
78  void getNextFrameRGBD(
79  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
80  bool& hardware_error, unsigned sensor_id = 0);
81 
82  /** @name Open/Close device methods
83  @{ */
84  /** Try to open the camera (all the parameters [resolution,fps,...] must be
85  * set before calling this) - users may also call initialize(), which in
86  * turn calls this method.
87  * Raises an exception upon error.
88  * \exception std::exception A textual description of the error.
89  */
90  void open(unsigned sensor_id = 0);
91 
92  /** Open a set of RGBD devices specified by their serial number. Raises an
93  * exception when the demanded serial numbers
94  * are not among the connected devices. This function also fills a vector
95  * with the serial numbers of the connected
96  * OpenNI2 sensors (this requires openning the sensors which are still
97  * closed to read their serial)
98  */
99  unsigned int openDevicesBySerialNum(
100  const std::set<unsigned>& vSerialRequired);
101 
102  /** Open a RGBD device specified by its serial number. This method is a
103  * wrapper for
104  * openDevicesBySerialNum(const std::set<unsigned>& vSerialRequired)
105  * This method requires to open the sensors which are still closed to read
106  * their serial.
107  */
108  unsigned int openDeviceBySerial(const unsigned int SerialRequired);
109 
110  /** Get the ID of the device corresponding to 'SerialRequired'.
111  */
113  const unsigned int SerialRequired, int& sensor_id) const;
114  /** Open all sensor streams (normally called automatically at constructor,
115  * no need to call it manually). \return false on error \sa kill() to close
116  */
117  bool start();
118  /** Kill the OpenNI2 driver \sa start()
119  */
120  void kill();
121  /** Whether there is a working connection to the sensor
122  */
123  bool isOpen(const unsigned sensor_id) const;
124  /** Close the connection to the sensor (no need to call it manually unless
125  * desired for some reason, since it's called at destructor
126  */
127  void close(unsigned sensor_id = 0);
128  /** The number of available devices at initialization
129  */
130  int getNumDevices() const;
131  /** Get a list of the connected OpenNI2 sensors.
132  */
133  int getConnectedDevices();
134 
135  /** @} */
136 
137  void setVerbose(bool verbose);
138  bool isVerbose() const;
139 
140  bool getColorSensorParam(
141  mrpt::img::TCamera& param, unsigned sensor_id = 0) const;
142  bool getDepthSensorParam(
143  mrpt::img::TCamera& param, unsigned sensor_id = 0) const;
144 
145  class CDevice;
146 
147  protected:
148  /** A vector with the serial numbers of the available devices */
149  std::vector<int> vSerialNums;
150 
151  /** The same options (width, height and fps) are set for all the sensors.
152  * (This could be changed if necessary) */
153  int m_width{640}, m_height{480};
154  float m_fps{30.0f};
156  bool m_verbose{false};
157  void showLog(const std::string& message) const;
158  /** The data that the RGBD sensors can return */
159  /** Default: all true
160  */
161  bool m_grab_image{true}, m_grab_depth{true}, m_grab_3D_points{true};
162 }; // End of class
163 } // namespace mrpt::hwdrivers
bool m_grab_image
The data that the RGBD sensors can return.
int getNumDevices() const
The number of available devices at initialization.
bool getDepthSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
void getNextFrameRGB(mrpt::img::CImage &rgb_img, mrpt::system::TTimeStamp &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().
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
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().
Contains classes for various device interfaces.
COpenNI2Generic()
Default ctor (width=640, height=480, fps=30)
int m_width
The same options (width, height and fps) are set for all the sensors.
void kill()
Kill the OpenNI2 driver.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
unsigned int openDeviceBySerial(const unsigned int SerialRequired)
Open a RGBD device specified by its serial number.
bool start()
Open all sensor streams (normally called automatically at constructor, no need to call it manually)...
void getNextFrameD(mrpt::math::CMatrix_u16 &depth_img_mm, mrpt::system::TTimeStamp &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 getColorSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
bool isOpen(const unsigned sensor_id) const
Whether there is a working connection to the sensor.
static int getNumInstances()
Get the number of OpenNI2 cameras currently open via COpenNI2Generic.
void close(unsigned sensor_id=0)
Close the connection to the sensor (no need to call it manually unless desired for some reason...
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:26
An abstract class for accessing OpenNI2 compatible sensors.
std::vector< int > vSerialNums
A vector with the serial numbers of the available devices.
unsigned int openDevicesBySerialNum(const std::set< unsigned > &vSerialRequired)
Open a set of RGBD devices specified by their serial number.
void open(unsigned sensor_id=0)
Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - us...
bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int &sensor_id) const
Get the ID of the device corresponding to &#39;SerialRequired&#39;.
int getConnectedDevices()
Get a list of the connected OpenNI2 sensors.
void showLog(const std::string &message) const
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:148



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020