MRPT  1.9.9
COpenNI2Sensor.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-2018, 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_COpenNI2Sensor_H
10 #define mrpt_COpenNI2Sensor_H
11 
16 
17 namespace mrpt::hwdrivers
18 {
19 /** A class for grabing "range images", intensity images (either RGB or IR) and
20  *other information from an OpenNI2 sensor.
21  * This class permits to access several sensors simultaneously. The same
22  *options (resolution, fps, etc.) are used for every sensor.
23  *
24  * <h2>Configuration and usage:</h2> <hr>
25  * Data is returned as observations of type mrpt::obs::CObservation3DRangeScan.
26  * See those classes for documentation on their fields.
27  *
28  * As with any other CGenericSensor class, the normal sequence of methods to be
29  *called is:
30  * - CGenericSensor::loadConfig() - Or calls to the individual setXXX() to
31  *configure the sensor parameters.
32  * - COpenNI2Sensor::initialize() - to start the communication with the
33  *sensor.
34  * - call COpenNI2Sensor::getNextObservation() for getting the data.
35  *
36  * <h2>Calibration parameters</h2><hr>
37  * In this class we employ the OpenNI2 method to return depth images refered
38  *to the RGB camera. Otherwise we could specify
39  * an accurate transformation of depth images to 3D points, you'll have to
40  *calibrate your RGBD sensor for that, and supply
41  * the following <b>threee pieces of information</b> (default calibration
42  *data will be used otherwise, but they'll be not optimal for all sensors!):
43  * - Camera parameters for the RGB camera. See
44  *COpenNI2Sensor::setCameraParamsIntensity()
45  * - Camera parameters for the depth camera. See
46  *COpenNI2Sensor::setCameraParamsDepth()
47  * - The 3D relative pose of the two cameras. See
48  *COpenNI2Sensor::setRelativePoseIntensityWrtDepth()
49  *
50  * See http://www.mrpt.org/Kinect_calibration for a procedure to calibrate
51  *RGBD sensors with an interactive GUI program.
52  *
53  * <h2>Coordinates convention</h2><hr>
54  * The origin of coordinates is the focal point of the depth camera, with the
55  *axes oriented as in the
56  * diagram shown in mrpt::obs::CObservation3DRangeScan. Notice in that
57  *picture that the RGB camera is
58  * assumed to have axes as usual in computer vision, which differ from those
59  *for the depth camera.
60  *
61  * The X,Y,Z axes used to report the data from accelerometers coincide with
62  *those of the depth camera
63  * (e.g. the camera standing on a table would have an ACC_Z=-9.8m/s2).
64  *
65  * Notice however that, for consistency with stereo cameras, when loading the
66  *calibration parameters from
67  * a configuration file, the left-to-right pose increment is expected as if
68  *both RGB & IR cameras had
69  * their +Z axes pointing forward, +X to the right, +Y downwards (just like
70  *it's the standard in stereo cameras
71  * and in computer vision literature). In other words: the pose stored in
72  *this class uses a different
73  * axes convention for the depth camera than in a stereo camera, so when a
74  *pose L2R is loaded from a calibration file
75  * it's actually converted like:
76  *
77  * L2R(this class convention) = CPose3D(0,0,0,-90deg,0deg,-90deg) (+)
78  *L2R(in the config file)
79  *
80  *
81  * <h2>Some general comments</h2><hr>
82  * - Depth is grabbed in millimeters
83  * - This sensor can be also used from within rawlog-grabber to grab
84  *datasets
85  *within a robot with more sensors.
86  * - There is no built-in threading support, so if you use this class
87  *manually
88  *(not with-in rawlog-grabber),
89  * the ideal would be to create a thread and continuously request data
90  *from
91  *that thread (see mrpt::system::createThread ).
92  * - The intensity channel default to the RGB images, but it can be changed
93  *with setVideoChannel() to read the IR camera images (useful for calibrating).
94  * - There is a built-in support for an optional preview of the data on a
95  *window, so you don't need to even worry on creating a window to show them.
96  * - This class relies on an embedded version of libfreenect (you do NOT
97  *need
98  *to install it in your system). Thanks guys for the great job!
99  *
100  * <h2>Converting to 3D point cloud </h2><hr>
101  * You can convert the 3D observation into a 3D point cloud with this piece
102  *of code:
103  *
104  * \code
105  * mrpt::obs::CObservation3DRangeScan obs3D;
106  * mrpt::maps::CColouredPointsMap pntsMap;
107  * pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;
108  * pntsMap.loadFromRangeScan(obs3D);
109  * \endcode
110  *
111  * Then the point cloud mrpt::maps::CColouredPointsMap can be converted into
112  *an OpenGL object for
113  * rendering with mrpt::maps::CMetricMap::getAs3DObject() or alternatively
114  *with:
115  *
116  * \code
117  * mrpt::opengl::CPointCloudColoured::Ptr gl_points =
118  *mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
119  * gl_points->loadFromPointsMap(&pntsMap);
120  * \endcode
121  *
122  *
123  * <h2>Platform-specific comments</h2><hr>
124  * For more details, refer to <a href="http://openkinect.org/wiki/Main_Page"
125  *>libfreenect</a> documentation:
126  * - Linux: You'll need root privileges to access Kinect. Or, install
127  *<code>
128  *MRPT/scripts/51-kinect.rules </code> in <code>/etc/udev/rules.d/</code> to
129  *allow access to all users.
130  * - Windows:
131  * - Since MRPT 0.9.4 you'll only need to install <a
132  *href="http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/"
133  *>libusb-win32</a>: download and extract the latest
134  *libusb-win32-bin-x.x.x.x.zip
135  * - To install the drivers, read this:
136  *http://openkinect.org/wiki/Getting_Started#Windows
137  * - MacOS: (write me!)
138  *
139  *
140  * <h2>Format of parameters for loading from a .ini file</h2><hr>
141  *
142  * \code
143  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
144  * -------------------------------------------------------
145  * [supplied_section_name]
146  * sensorLabel = OPENNI2 // A text description
147  * preview_window = false // Show a window with a preview of the
148  *grabbed data in real-time
149  *
150  * device_number = 0 // Device index to open (0:first Kinect,
151  *1:second Kinect,...)
152  *
153  * grab_image = true // Grab the RGB image channel?
154  *(Default=true)
155  * grab_depth = true // Grab the depth channel? (Default=true)
156  * grab_3D_points = true // Grab the 3D point cloud? (Default=true)
157  *If disabled, points can be generated later on.
158  *
159  * video_channel = VIDEO_CHANNEL_RGB // Optional. Can be:
160  *VIDEO_CHANNEL_RGB (default) or VIDEO_CHANNEL_IR
161  *
162  * pose_x=0 // Camera position in the robot (meters)
163  * pose_y=0
164  * pose_z=0
165  * pose_yaw=0 // Angles in degrees
166  * pose_pitch=0
167  * pose_roll=0
168  *
169  *
170  * // Kinect sensor calibration:
171  * // See http://www.mrpt.org/Kinect_and_MRPT
172  *
173  * // Left/Depth camera
174  * [supplied_section_name_LEFT]
175  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
176  *section (it is not a separate device!)
177  *
178  * resolution = [640 488]
179  * cx = 314.649173
180  * cy = 240.160459
181  * fx = 572.882768
182  * fy = 542.739980
183  * dist = [-4.747169e-03 -4.357976e-03 0.000000e+00 0.000000e+00
184  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
185  *
186  * // Right/RGB camera
187  * [supplied_section_name_RIGHT]
188  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
189  *section (it is not a separate device!)
190  *
191  * resolution = [640 480]
192  * cx = 322.515987
193  * cy = 259.055966
194  * fx = 521.179233
195  * fy = 493.033034
196  * dist = [5.858325e-02 3.856792e-02 0.000000e+00 0.000000e+00
197  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
198  *
199  * // Relative pose of the right camera wrt to the left camera:
200  * // This assumes that both camera frames are such that +Z points
201  * // forwards, and +X and +Y to the right and downwards.
202  * // For the actual coordinates employed in 3D observations, see figure in
203  *mrpt::obs::CObservation3DRangeScan
204  * [supplied_section_name_LEFT2RIGHT_POSE]
205  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
206  *section (it is not a separate device!)
207  *
208  * pose_quaternion = [0.025575 -0.000609 -0.001462 0.999987 0.002038
209  *0.004335 -0.001693]
210  *
211  * \endcode
212  *
213  * More references to read:IMPEXP mrpt
214  * - http://http://www.openni.org/
215  * \ingroup mrpt_hwdrivers_grp
216  */
219 {
221 
222  public:
223  /** Default ctor
224  */
225  COpenNI2Sensor();
226  /** Default ctor
227  */
228  ~COpenNI2Sensor();
229 
230  /** Set the serial number of the device to open.
231  * \exception This method must throw an exception when such serial number
232  * is not found among the connected devices.
233  */
234  inline void setSerialToOpen(const unsigned serial)
235  {
236  m_serial_number = serial;
237  }
238 
239  /** Set the sensor_id of the device to open.
240  * \exception This method must throw an exception when such serial number
241  * is not found among the connected devices.
242  */
243  inline void setSensorIDToOpen(const unsigned sensor_id)
244  {
245  m_user_device_number = sensor_id;
246  }
247 
248  /** Initializes the 3D camera - should be invoked after calling loadConfig()
249  * or setting the different parameters with the set*() methods.
250  * \exception This method must throw an exception with a descriptive
251  * message if some critical error is found.
252  */
253  virtual void initialize();
254 
255  /** To be called at a high rate (>XX Hz), this method populates the
256  * internal buffer of received observations.
257  * This method is mainly intended for usage within rawlog-grabber or
258  * similar programs.
259  * For an alternative, see getNextObservation()
260  * \exception This method must throw an exception with a descriptive
261  * message if some critical error is found.
262  * \sa getNextObservation
263  */
264  virtual void doProcess();
265 
266  /** The main data retrieving function, to be called after calling
267  * loadConfig() and initialize().
268  * \param out_obs The output retrieved observation (only if
269  * there_is_obs=true).
270  * \param there_is_obs If set to false, there was no new observation.
271  * \param hardware_error True on hardware/comms error.
272  *
273  * \sa doProcess
274  */
275  void getNextObservation(
276  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
277  bool& hardware_error);
278 
279  /** Set the path where to save off-rawlog image files (this class DOES take
280  * into account this path).
281  * An empty string (the default value at construction) means to save
282  * images embedded in the rawlog, instead of on separate files.
283  * \exception std::exception If the directory doesn't exists and cannot be
284  * created.
285  */
286  virtual void setPathForExternalImages(const std::string& directory);
287 
288  /** @name Sensor parameters (alternative to \a loadConfig ) and manual
289  control
290  @{ */
291 
292  /** Get the maximum range (meters) that can be read in the observation field
293  * "rangeImage" */
294  inline double getMaxRange() const { return m_maxRange; }
295  /** Get the row count in the camera images, loaded automatically upon camera
296  * open(). */
297  inline size_t rows() const { return m_cameraParamsRGB.nrows; }
298  /** Get the col count in the camera images, loaded automatically upon camera
299  * open(). */
300  inline size_t cols() const { return m_cameraParamsRGB.ncols; }
301  /** Get a const reference to the depth camera calibration parameters */
303  {
304  return m_cameraParamsRGB;
305  }
307  {
309  }
310 
311  /** Get a const reference to the depth camera calibration parameters */
313  {
314  return m_cameraParamsDepth;
315  }
317  {
319  }
320 
321  /** Set the pose of the intensity camera wrt the depth camera \sa See
322  * mrpt::obs::CObservation3DRangeScan for a 3D diagram of this pose */
324  {
326  }
328  {
330  }
331 
332  /** Enable/disable the grabbing of the RGB channel */
333  inline void enableGrabRGB(bool enable = true) { m_grab_image = enable; }
334  inline bool isGrabRGBEnabled() const { return m_grab_image; }
335  /** Enable/disable the grabbing of the depth channel */
336  inline void enableGrabDepth(bool enable = true) { m_grab_depth = enable; }
337  inline bool isGrabDepthEnabled() const { return m_grab_depth; }
338  /** Enable/disable the grabbing of the 3D point clouds */
339  inline void enableGrab3DPoints(bool enable = true)
340  {
341  m_grab_3D_points = enable;
342  }
343  inline bool isGrab3DPointsEnabled() const { return m_grab_3D_points; }
344  /** @} */
345 
346  protected:
347  virtual void loadConfig_sensorSpecific(
348  const mrpt::config::CConfigFileBase& configSource,
349  const std::string& section);
350 
352 
353  /** Show preview window while grabbing
354  */
356  /** If preview is enabled, only show 1 out of N images.
357  */
361 
362  /** Params for the RGB camera
363  */
365  /** Params for the Depth camera
366  */
368  /** See mrpt::obs::CObservation3DRangeScan for a diagram of this pose
369  */
371 
372  /** Sensor max range (meters)
373  */
374  double m_maxRange;
375 
376  /** Number of device to open (0:first,...)
377  */
379  /** Serial number of device to open
380  */
382 
383 }; // End of class
384 }
385 #endif
386 
387 
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
void setCameraParamsIntensity(const mrpt::img::TCamera &p)
bool m_grab_image
The data that the RGBD sensors can return.
uint32_t nrows
Definition: TCamera.h:39
const mrpt::img::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
mrpt::gui::CDisplayWindow::Ptr m_win_int
mrpt::gui::CDisplayWindow::Ptr m_win_range
void getNextObservation(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error)
The main data retrieving function, to be called after calling loadConfig() and initialize().
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.
Contains classes for various device interfaces.
size_t cols() const
Get the col count in the camera images, loaded automatically upon camera open().
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
This class allows loading and storing values and vectors of different types from a configuration text...
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
mrpt::img::TCamera m_cameraParamsRGB
Params for the RGB camera.
int m_serial_number
Serial number of device to open.
const mrpt::img::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
void setSerialToOpen(const unsigned serial)
Set the serial number of the device to open.
virtual void setPathForExternalImages(const std::string &directory)
Set the path where to save off-rawlog image files (this class DOES take into account this path)...
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:27
An abstract class for accessing OpenNI2 compatible sensors.
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
mrpt::poses::CPose3D m_sensorPoseOnRobot
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
GLsizei const GLchar ** string
Definition: glext.h:4101
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
void setSensorIDToOpen(const unsigned sensor_id)
Set the sensor_id of the device to open.
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
void setCameraParamsDepth(const mrpt::img::TCamera &p)
double m_maxRange
Sensor max range (meters)
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
int m_user_device_number
Number of device to open (0:first,...)
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
size_t rows() const
Get the row count in the camera images, loaded automatically upon camera open().
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
virtual void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see config::CConfigFileBase and derived classes)
bool m_preview_window
Show preview window while grabbing.
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
GLfloat GLfloat p
Definition: glext.h:6305
uint32_t ncols
Camera resolution.
Definition: TCamera.h:39



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020