Point Cloud Library (PCL)  1.11.1-dev
ensenso_grabber.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2014-, Open Perception, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Victor Lamoine (victor.lamoine@gmail.com)
37  */
38 
39 #pragma once
40 
41 #include <pcl/pcl_config.h>
42 
43 #include <pcl/common/time.h>
44 #include <pcl/common/io.h>
45 #include <Eigen/Geometry>
46 #include <Eigen/StdVector>
47 #include <pcl/io/boost.h>
48 
49 #include <pcl/io/grabber.h>
50 #include <pcl/common/synchronizer.h>
51 
52 #include <nxLib.h> // Ensenso SDK
53 
54 #include <thread>
55 
56 namespace pcl
57 {
58  struct PointXYZ;
59  template <typename T> class PointCloud;
60 
61  /** @brief Grabber for IDS-Imaging Ensenso's devices.\n
62  * The [Ensenso SDK](http://www.ensenso.de/manual/) allow to use multiple Ensenso devices to produce a single cloud.\n
63  * This feature is not implemented here, it is up to the user to configure multiple Ensenso cameras.\n
64  * @author Victor Lamoine (victor.lamoine@gmail.com)\n
65  * @ingroup io
66  */
68  {
69  using PairOfImages = std::pair<pcl::PCLImage, pcl::PCLImage>;
70 
71  public:
72  /** @cond */
73  using Ptr = shared_ptr<EnsensoGrabber>;
74  using ConstPtr = shared_ptr<const EnsensoGrabber>;
75 
76  // Define callback signature typedefs
77  using sig_cb_ensenso_point_cloud = void(const pcl::PointCloud<pcl::PointXYZ>::Ptr&);
78 
79  using sig_cb_ensenso_images = void(const shared_ptr<PairOfImages>&);
80 
81  using sig_cb_ensenso_point_cloud_images = void(const pcl::PointCloud<pcl::PointXYZ>::Ptr&,const shared_ptr<PairOfImages>&);
82 
83  /** @endcond */
84 
85  /** @brief Constructor */
86  EnsensoGrabber ();
87 
88  /** @brief Destructor inherited from the Grabber interface. It never throws. */
89  virtual
90  ~EnsensoGrabber () noexcept;
91 
92  /** @brief Searches for available devices
93  * @returns The number of Ensenso devices connected */
94  int
95  enumDevices () const;
96 
97  /** @brief Opens an Ensenso device
98  * @param[in] device The device ID to open
99  * @return True if successful, false otherwise */
100  bool
101  openDevice (const int device = 0);
102 
103  /** @brief Closes the Ensenso device
104  * @return True if successful, false otherwise */
105  bool
106  closeDevice ();
107 
108  /** @brief Start the point cloud and or image acquisition
109  * @note Opens device "0" if no device is open */
110  void
111  start ();
112 
113  /** @brief Stop the data acquisition */
114  void
115  stop ();
116 
117  /** @brief Check if the data acquisition is still running
118  * @return True if running, false otherwise */
119  bool
120  isRunning () const;
121 
122  /** @brief Check if a TCP port is opened
123  * @return True if open, false otherwise */
124  bool
125  isTcpPortOpen () const;
126 
127  /** @brief Get class name
128  * @returns A string containing the class name */
129  std::string
130  getName () const;
131 
132  /** @brief Configure Ensenso capture settings
133  * @param[in] auto_exposure If set to yes, the exposure parameter will be ignored
134  * @param[in] auto_gain If set to yes, the gain parameter will be ignored
135  * @param[in] bining Pixel bining: 1, 2 or 4
136  * @param[in] exposure In milliseconds, from 0.01 to 20 ms
137  * @param[in] front_light Infrared front light (useful for calibration)
138  * @param[in] gain Float between 1 and 4
139  * @param[in] gain_boost
140  * @param[in] hardware_gamma
141  * @param[in] hdr High Dynamic Range (check compatibility with other options in Ensenso manual)
142  * @param[in] pixel_clock In MegaHertz, from 5 to 85
143  * @param[in] projector Use the central infrared projector or not
144  * @param[in] target_brightness Between 40 and 210
145  * @param[in] trigger_mode
146  * @param[in] use_disparity_map_area_of_interest
147  * @return True if successful, false otherwise
148  * @note See [Capture tree item](http://www.ensenso.de/manual/index.html?capture.htm) for more
149  * details about the parameters. */
150  bool
151  configureCapture (const bool auto_exposure = true,
152  const bool auto_gain = true,
153  const int bining = 1,
154  const float exposure = 0.32,
155  const bool front_light = false,
156  const int gain = 1,
157  const bool gain_boost = false,
158  const bool hardware_gamma = false,
159  const bool hdr = false,
160  const int pixel_clock = 10,
161  const bool projector = true,
162  const int target_brightness = 80,
163  const std::string trigger_mode = "Software",
164  const bool use_disparity_map_area_of_interest = false) const;
165 
166  /** @brief Capture a single point cloud and store it
167  * @param[out] cloud The cloud to be filled
168  * @return True if successful, false otherwise
169  * @warning A device must be opened and not running */
170  bool
171  grabSingleCloud (pcl::PointCloud<pcl::PointXYZ> &cloud) const;
172 
173  /** @brief Set up the Ensenso sensor and API to do 3D extrinsic calibration using the Ensenso 2D patterns
174  * @param[in] grid_spacing
175  * @return True if successful, false otherwise
176  *
177  * Configures the capture parameters to default values (eg: @c projector = @c false and @c front_light = @c true)
178  * Discards all previous patterns, configures @c grid_spacing
179  * @warning A device must be opened and must not be running.
180  * @note See the [Ensenso manual](http://www.ensenso.de/manual/index.html?calibratehandeyeparameters.htm) for more
181  * information about the extrinsic calibration process.
182  * @note [GridSize](http://www.ensenso.de/manual/index.html?gridsize.htm) item is protected in the NxTree, you can't modify it.
183  */
184  bool
185  initExtrinsicCalibration (const int grid_spacing) const;
186 
187  /** @brief Clear calibration patterns buffer */
188  bool
189  clearCalibrationPatternBuffer () const;
190 
191  /** @brief Captures a calibration pattern
192  * @return the number of calibration patterns stored in the nxTree, -1 on error
193  * @warning A device must be opened and must not be running.
194  * @note You should use @ref initExtrinsicCalibration before */
195  int
196  captureCalibrationPattern () const;
197 
198  /** @brief Estimate the calibration pattern pose
199  * @param[out] pattern_pose the calibration pattern pose
200  * @return true if successful, false otherwise
201  * @warning A device must be opened and must not be running.
202  * @note At least one calibration pattern must have been captured before, use @ref captureCalibrationPattern before */
203  bool
204  estimateCalibrationPatternPose (Eigen::Affine3d &pattern_pose) const;
205 
206  /** @brief Computes the calibration matrix using the collected patterns and the robot poses vector
207  * @param[in] robot_poses A list of robot poses, 1 for each pattern acquired (in the same order)
208  * @param[out] json The extrinsic calibration data in JSON format
209  * @param[in] setup Moving or Fixed, please refer to the Ensenso documentation
210  * @param[in] target Please refer to the Ensenso documentation
211  * @param[in] guess_tf Guess transformation for the calibration matrix (translation in meters)
212  * @param[in] pretty_format JSON formatting style
213  * @return True if successful, false otherwise
214  * @warning This can take up to 120 seconds
215  * @note Check the result with @ref getResultAsJson.
216  * If you want to permanently store the result, use @ref storeEEPROMExtrinsicCalibration. */
217  bool
218  computeCalibrationMatrix (const std::vector<Eigen::Affine3d, Eigen::aligned_allocator<Eigen::Affine3d> > &robot_poses,
219  std::string &json,
220  const std::string setup = "Moving", // Default values: Moving or Fixed
221  const std::string target = "Hand", // Default values: Hand or Workspace
222  const Eigen::Affine3d &guess_tf = Eigen::Affine3d::Identity (),
223  const bool pretty_format = true) const;
224 
225  /** @brief Copy the link defined in the Link node of the nxTree to the EEPROM
226  * @return True if successful, false otherwise
227  * Refer to @ref setExtrinsicCalibration for more information about how the EEPROM works.\n
228  * After calling @ref computeCalibrationMatrix, this enables to permanently store the matrix.
229  * @note The target must be specified (@ref computeCalibrationMatrix specifies the target) */
230  bool
231  storeEEPROMExtrinsicCalibration () const;
232 
233  /** @brief Clear the extrinsic calibration stored in the EEPROM by writing an identity matrix
234  * @return True if successful, false otherwise */
235  bool
236  clearEEPROMExtrinsicCalibration ();
237 
238  /** @brief Update Link node in NxLib tree
239  * @param[in] target "Hand" or "Workspace" for example
240  * @param[in] euler_angle
241  * @param[in] rotation_axis
242  * @param[in] translation Translation in meters
243  * @return True if successful, false otherwise
244  * @warning Translation are in meters, rotation angles in radians! (stored in mm/radians in Ensenso tree)
245  * @note If a calibration has been stored in the EEPROM, it is copied in the Link node at nxLib tree start.
246  * This method overwrites the Link node but does not write to the EEPROM.
247  *
248  * More information on the parameters can be found in [Link node](http://www.ensenso.de/manual/index.html?cameralink.htm)
249  * section of the Ensenso manual.
250  *
251  * The point cloud you get from the Ensenso is already transformed using this calibration matrix.
252  * Make sure it is the identity transformation if you want the original point cloud! (use @ref clearEEPROMExtrinsicCalibration)
253  * Use @ref storeEEPROMExtrinsicCalibration to permanently store this transformation */
254  bool
255  setExtrinsicCalibration (const double euler_angle,
256  Eigen::Vector3d &rotation_axis,
257  const Eigen::Vector3d &translation,
258  const std::string target = "Hand") const;
259 
260  /** @brief Update Link node in NxLib tree with an identity matrix
261  * @param[in] target "Hand" or "Workspace" for example
262  * @return True if successful, false otherwise */
263  bool
264  setExtrinsicCalibration (const std::string target = "Hand");
265 
266  /** @brief Update Link node in NxLib tree
267  * @param[in] transformation Transformation matrix
268  * @param[in] target "Hand" or "Workspace" for example
269  * @return True if successful, false otherwise
270  * @warning Translation are in meters, rotation angles in radians! (stored in mm/radians in Ensenso tree)
271  * @note If a calibration has been stored in the EEPROM, it is copied in the Link node at nxLib tree start.
272  * This method overwrites the Link node but does not write to the EEPROM.
273  *
274  * More information on the parameters can be found in [Link node](http://www.ensenso.de/manual/index.html?cameralink.htm)
275  * section of the Ensenso manual.
276  *
277  * The point cloud you get from the Ensenso is already transformed using this calibration matrix.
278  * Make sure it is the identity transformation if you want the original point cloud! (use @ref clearEEPROMExtrinsicCalibration)
279  * Use @ref storeEEPROMExtrinsicCalibration to permanently store this transformation */
280  bool
281  setExtrinsicCalibration (const Eigen::Affine3d &transformation,
282  const std::string target = "Hand");
283 
284  /** @brief Obtain the number of frames per second (FPS) */
285  float
286  getFramesPerSecond () const;
287 
288  /** @brief Open TCP port to enable access via the [nxTreeEdit](http://www.ensenso.de/manual/software_components.htm) program.
289  * @param[in] port The port number
290  * @return True if successful, false otherwise */
291  bool
292  openTcpPort (const int port = 24000);
293 
294  /** @brief Close TCP port program
295  * @return True if successful, false otherwise
296  * @warning If you do not close the TCP port the program might exit with the port still open, if it is the case
297  * use @code ps -ef @endcode and @code kill PID @endcode to kill the application and effectively close the port. */
298  bool
299  closeTcpPort (void);
300 
301  /** @brief Returns the full NxLib tree as a JSON string
302  * @param[in] pretty_format JSON formatting style
303  * @return A string containing the NxLib tree in JSON format */
304  std::string
305  getTreeAsJson (const bool pretty_format = true) const;
306 
307  /** @brief Returns the Result node (of the last command) as a JSON string
308  * @param[in] pretty_format JSON formatting style
309  * @return A string containing the Result node in JSON format
310  */
311  std::string
312  getResultAsJson (const bool pretty_format = true) const;
313 
314  /** @brief Get the Euler angles corresponding to a JSON string (an angle axis transformation)
315  * @param[in] json A string containing the angle axis transformation in JSON format
316  * @param[out] x The X translation
317  * @param[out] y The Y translation
318  * @param[out] z The Z translation
319  * @param[out] w The yaW angle
320  * @param[out] p The Pitch angle
321  * @param[out] r The Roll angle
322  * @return True if successful, false otherwise
323  * @warning The units are meters and radians!
324  * @note See: [transformation page](http://www.ensenso.de/manual/transformation.htm) in the EnsensoSDK documentation
325  */
326  bool
327  jsonTransformationToEulerAngles (const std::string &json,
328  double &x,
329  double &y,
330  double &z,
331  double &w,
332  double &p,
333  double &r) const;
334 
335  /** @brief Get the angle axis parameters corresponding to a JSON string
336  * @param[in] json A string containing the angle axis transformation in JSON format
337  * @param[out] alpha Euler angle
338  * @param[out] axis Axis vector
339  * @param[out] translation Translation vector
340  * @return True if successful, false otherwise
341  * @warning The units are meters and radians!
342  * @note See: [transformation page](http://www.ensenso.de/manual/transformation.htm) in the EnsensoSDK documentation
343  */
344  bool
345  jsonTransformationToAngleAxis (const std::string json,
346  double &alpha,
347  Eigen::Vector3d &axis,
348  Eigen::Vector3d &translation) const;
349 
350 
351  /** @brief Get the JSON string corresponding to a 4x4 matrix
352  * @param[in] transformation The input transformation
353  * @param[out] matrix A matrix containing JSON transformation
354  * @return True if successful, false otherwise
355  * @warning The units are meters and radians!
356  * @note See: [ConvertTransformation page](http://www.ensenso.de/manual/index.html?cmdconverttransformation.htm) in the EnsensoSDK documentation
357  */
358  bool
359  jsonTransformationToMatrix (const std::string transformation,
360  Eigen::Affine3d &matrix) const;
361 
362 
363  /** @brief Get the JSON string corresponding to the Euler angles transformation
364  * @param[in] x The X translation
365  * @param[in] y The Y translation
366  * @param[in] z The Z translation
367  * @param[in] w The yaW angle
368  * @param[in] p The Pitch angle
369  * @param[in] r The Roll angle
370  * @param[out] json A string containing the Euler angles transformation in JSON format
371  * @param[in] pretty_format JSON formatting style
372  * @return True if successful, false otherwise
373  * @warning The units are meters and radians!
374  * @note See: [transformation page](http://www.ensenso.de/manual/transformation.htm) in the EnsensoSDK documentation
375  */
376  bool
377  eulerAnglesTransformationToJson (const double x,
378  const double y,
379  const double z,
380  const double w,
381  const double p,
382  const double r,
383  std::string &json,
384  const bool pretty_format = true) const;
385 
386  /** @brief Get the JSON string corresponding to an angle axis transformation
387  * @param[in] x The X angle
388  * @param[in] y The Y angle
389  * @param[in] z The Z angle
390  * @param[in] rx The X component of the Euler axis
391  * @param[in] ry The Y component of the Euler axis
392  * @param[in] rz The Z component of the Euler axis
393  * @param[in] alpha The Euler rotation angle
394  * @param[out] json A string containing the angle axis transformation in JSON format
395  * @param[in] pretty_format JSON formatting style
396  * @return True if successful, false otherwise
397  * @warning The units are meters and radians! (the Euler axis doesn't need to be normalized)
398  * @note See: [transformation page](http://www.ensenso.de/manual/transformation.htm) in the EnsensoSDK documentation
399  */
400  bool
401  angleAxisTransformationToJson (const double x,
402  const double y,
403  const double z,
404  const double rx,
405  const double ry,
406  const double rz,
407  const double alpha,
408  std::string &json,
409  const bool pretty_format = true) const;
410 
411  /** @brief Get the JSON string corresponding to a 4x4 matrix
412  * @param[in] matrix The input matrix
413  * @param[out] json A string containing the matrix transformation in JSON format
414  * @param[in] pretty_format JSON formatting style
415  * @return True if successful, false otherwise
416  * @warning The units are meters and radians!
417  * @note See: [ConvertTransformation page](http://www.ensenso.de/manual/index.html?cmdconverttransformation.htm)
418  * in the EnsensoSDK documentation */
419  bool
420  matrixTransformationToJson (const Eigen::Affine3d &matrix,
421  std::string &json,
422  const bool pretty_format = true) const;
423 
424  /** @brief Reference to the NxLib tree root
425  * @warning You must handle NxLib exceptions manually when playing with @ref root_ !
426  * See ensensoExceptionHandling in ensenso_grabber.cpp */
427  shared_ptr<const NxLibItem> root_;
428 
429  /** @brief Reference to the camera tree
430  * @warning You must handle NxLib exceptions manually when playing with @ref camera_ ! */
431  NxLibItem camera_;
432 
433  protected:
434  /** @brief Grabber thread */
435  std::thread grabber_thread_;
436 
437  /** @brief Boost point cloud signal */
438  boost::signals2::signal<sig_cb_ensenso_point_cloud>* point_cloud_signal_;
439 
440  /** @brief Boost images signal */
441  boost::signals2::signal<sig_cb_ensenso_images>* images_signal_;
442 
443  /** @brief Boost images + point cloud signal */
444  boost::signals2::signal<sig_cb_ensenso_point_cloud_images>* point_cloud_images_signal_;
445 
446  /** @brief Whether an Ensenso device is opened or not */
448 
449  /** @brief Whether an TCP port is opened or not */
450  bool tcp_open_;
451 
452  /** @brief Whether an Ensenso device is running or not */
453  bool running_;
454 
455  /** @brief Point cloud capture/processing frequency */
457 
458  /** @brief Mutual exclusion for FPS computation */
459  mutable std::mutex fps_mutex_;
460 
461  /** @brief Convert an Ensenso time stamp into a PCL/ROS time stamp
462  * @param[in] ensenso_stamp
463  * @return PCL stamp
464  * The Ensenso API returns the time elapsed from January 1st, 1601 (UTC); on Linux OS the reference time is January 1st, 1970 (UTC).
465  * See [time-stamp page](http://www.ensenso.de/manual/index.html?json_types.htm) for more info about the time stamp conversion. */
466  std::uint64_t
467  static
468  getPCLStamp (const double ensenso_stamp);
469 
470  /** @brief Get OpenCV image type corresponding to the parameters given
471  * @param channels number of channels in the image
472  * @param bpe bytes per element
473  * @param isFlt is float
474  * @return the OpenCV type as a string */
475  std::string
476  static
477  getOpenCVType (const int channels,
478  const int bpe,
479  const bool isFlt);
480 
481  /** @brief Continuously asks for images and or point clouds data from the device and publishes them if available.
482  * PCL time stamps are filled for both the images and clouds grabbed (see @ref getPCLStamp)
483  * @note The cloud time stamp is the RAW image time stamp */
484  void
485  processGrabbing ();
486  };
487 } // namespace pcl
pcl
Definition: convolution.h:46
pcl::EnsensoGrabber::images_signal_
boost::signals2::signal< sig_cb_ensenso_images > * images_signal_
Boost images signal.
Definition: ensenso_grabber.h:441
pcl::EnsensoGrabber::point_cloud_images_signal_
boost::signals2::signal< sig_cb_ensenso_point_cloud_images > * point_cloud_images_signal_
Boost images + point cloud signal.
Definition: ensenso_grabber.h:444
pcl::EnsensoGrabber::frequency_
pcl::EventFrequency frequency_
Point cloud capture/processing frequency.
Definition: ensenso_grabber.h:456
pcl::EnsensoGrabber::camera_
NxLibItem camera_
Reference to the camera tree.
Definition: ensenso_grabber.h:431
pcl::EnsensoGrabber::grabber_thread_
std::thread grabber_thread_
Grabber thread.
Definition: ensenso_grabber.h:435
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::EnsensoGrabber::device_open_
bool device_open_
Whether an Ensenso device is opened or not.
Definition: ensenso_grabber.h:447
pcl::Grabber
Grabber interface for PCL 1.x device drivers.
Definition: grabber.h:59
pcl::EnsensoGrabber::tcp_open_
bool tcp_open_
Whether an TCP port is opened or not.
Definition: ensenso_grabber.h:450
pcl::EnsensoGrabber::point_cloud_signal_
boost::signals2::signal< sig_cb_ensenso_point_cloud > * point_cloud_signal_
Boost point cloud signal.
Definition: ensenso_grabber.h:438
pcl::EventFrequency
A helper class to measure frequency of a certain event.
Definition: time.h:134
pcl::EnsensoGrabber::running_
bool running_
Whether an Ensenso device is running or not.
Definition: ensenso_grabber.h:453
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:406
pcl::EnsensoGrabber
Grabber for IDS-Imaging Ensenso's devices.
Definition: ensenso_grabber.h:67
time.h
pcl::EnsensoGrabber::root_
shared_ptr< const NxLibItem > root_
Reference to the NxLib tree root.
Definition: ensenso_grabber.h:427
PCL_EXPORTS
#define PCL_EXPORTS
Definition: pcl_macros.h:323
pcl::EnsensoGrabber::fps_mutex_
std::mutex fps_mutex_
Mutual exclusion for FPS computation.
Definition: ensenso_grabber.h:459