ensenso_grabber.h
Go to the documentation of this file.
1 #ifndef __ENSENSO_ENSENSO_GRABBER__
2 #define __ENSENSO_ENSENSO_GRABBER__
3 
4 // PCL
5 #include <pcl/pcl_config.h>
6 #include <pcl/common/io.h>
7 #include <pcl/common/time.h>
8 #include <pcl/common/transforms.h>
9 #include <pcl/io/eigen.h>
10 #include <pcl/io/boost.h>
11 #include <pcl/io/grabber.h>
12 #include <pcl/common/synchronizer.h>
13 // Others
14 #include <Eigen/Geometry>
15 #include <boost/thread.hpp>
16 #include <sensor_msgs/CameraInfo.h>
17 #include <geometry_msgs/TransformStamped.h>
18 // Ensenso SDK
19 #include <nxLib.h>
20 namespace pcl
21 {
22 template <typename T>
23 struct PCLGenImage : PCLImage
24 {
25  std::vector<T> data;
28 };
29 
30 struct Transform
31 {
32  double tx, ty, tz, qx, qy, qz, qw;
33 };
38 class PCL_EXPORTS EnsensoGrabber : public Grabber
39 {
40  typedef std::pair<pcl::PCLGenImage<pcl::uint8_t>, pcl::PCLGenImage<pcl::uint8_t> > PairOfImages;
41 
42 public:
43  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 
48 
49  // Define callback signature typedefs
50  typedef void
51  (sig_cb_ensenso_point_cloud)(const pcl::PointCloud<pcl::PointXYZ>::Ptr &);
52 
53  typedef void
54  (sig_cb_ensenso_point_cloud_rgb)(const pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &);
55 
56  typedef void
57  (sig_cb_ensenso_images)(const boost::shared_ptr<PairOfImages>&, const boost::shared_ptr<PairOfImages>&);
58 
59  typedef void
60  (sig_cb_ensenso_images_rgb)(const boost::shared_ptr<PairOfImages>&, const boost::shared_ptr<PairOfImages>&, const boost::shared_ptr<PairOfImages>&);
61 
62  typedef void
63  (sig_cb_ensenso_image_depth)(const boost::shared_ptr<pcl::PCLGenImage<float> >&);
64 
68  EnsensoGrabber ();
69 
71  virtual ~EnsensoGrabber () throw ();
72 
92  bool calibrateHandEye ( const std::vector<Eigen::Affine3d, Eigen::aligned_allocator<Eigen::Affine3d> > &robot_poses,
93  const Eigen::Affine3d &camera_seed,
94  const Eigen::Affine3d &pattern_seed,
95  const std::string setup,
96  Eigen::Affine3d &estimated_camera_pose,
97  Eigen::Affine3d &estimated_pattern_pose,
98  int &iterations,
99  double &reprojection_error) const;
100 
103  bool closeDevices ();
104 
109  bool closeTcpPort (void);
110 
115  int collectPattern (const bool buffer=true) const;
116 
119  double decodePattern () const;
120 
124  bool discardPatterns () const;
125 
128  int enumDevices () const;
129 
139  bool estimatePatternPose (Eigen::Affine3d &pose, const bool average=false) const;
140 
143  std::string getName () const;
144 
151  bool getCameraInfo(std::string cam, sensor_msgs::CameraInfo &cam_info) const;
152 
157  bool getTFLeftToRGB(Transform& tf) const;
158 
167  bool getLastCalibrationPattern (std::vector<int> &grid_size, double &grid_spacing,
168  std::vector<Eigen::Vector2d> &left_points,
169  std::vector<Eigen::Vector2d> &right_points,
170  Eigen::Affine3d &pose) const;
171 
173  float getFramesPerSecond () const;
174 
177  int getPatternCount () const;
178 
183  bool grabSingleCloud (pcl::PointCloud<pcl::PointXYZ> &cloud);
184 
187  bool isRunning () const;
188 
191  bool isTcpPortOpen () const;
192 
196  bool openDevice (std::string serial);
197 
198 
202  bool openMonoDevice (std::string serial);
203 
208  bool openTcpPort (const int port = 24000);
209 
212  bool restoreDefaultConfiguration () const;
213 
218  bool setEnableCUDA (const bool enable=true) const;
219 
223  bool setFindPattern (const bool enable=true);
224 
228  bool setUseRGB (const bool enable=true);
229 
233  bool setAutoBlackLevel (const bool enable=true) const;
234 
238  bool setAutoExposure (const bool enable=true) const;
239 
243  bool setAutoGain (const bool enable=true) const;
244 
253  bool setBinning (const int binning=1) const;
254 
260  bool setBlackLevelOffset (const float offset=1.0) const;
261 
267  bool setExposure (const float exposure=1.0) const;
268 
282  bool setFlexView (const bool enable=false, const int imagepairs=2) const;
283 
290  bool setFrontLight (const bool enable=false) const;
291 
297  bool setGain (const float gain=1.0) const;
298 
302  bool setGainBoost (const bool enable=false) const;
303 
307  bool setGridSpacing (const double grid_spacing) const;
308 
313  bool setHardwareGamma (const bool enable=true) const;
314 
319  bool setHdr (const bool enable=false) const;
320 
327  bool setMinimumDisparity (const int disparity=-64) const;
328 
335  bool setNumberOfDisparities (const int number=128) const;
336 
349  bool setOptimizationProfile (const std::string profile="AlignedAndDiagonal") const;
350 
357  bool setPixelClock (const int pixel_clock=24) const;
358 
364  bool setProjector (const bool enable=true) const;
365 
377  bool setScaling (const float scaling=1.0) const;
378 
382  bool setTargetBrightness (const int target=80) const;
383 
394  bool setTriggerMode (const std::string mode="Software") const;
395 
400  bool setRGBTriggerDelay (const float delay=10) const;
401 
406  bool setUseOpenGL (const bool enable) const;
407 
420  bool setUseDisparityMapAreaOfInterest (const bool enable=false) const;
421 
427  bool setDepthChangeCost(const int changecost) const;
428 
436  bool setDepthStepCost(const int stepcost) const;
437 
448  bool setShadowingThreshold(const int shadowingthreshold) const;
449 
456  bool setUniquenessRatio(const int ratio) const;
457 
465  bool setMedianFilterRadius(const int radius) const;
466 
477  bool setSpeckleComponentThreshold(const int threshold) const;
478 
485  bool setSpeckleRegionSize(const int threshold) const;
486 
492  bool setFillBorderSpread(const int maximumspread) const;
493 
499  bool setFillRegionSize(const int regionsize) const;
500 
504  bool setSurfaceConnectivity(const int threshold) const;
505 
510  bool setNearPlane(const int near);
511 
516  bool setFarPlane(const int far);
517 
518 
521  void start ();
522 
524  void stop ();
525 
528  void storeCalibrationPattern (const bool enable);
529 
530 protected:
532  boost::thread grabber_thread_;
533 
535  boost::signals2::signal<sig_cb_ensenso_point_cloud>* point_cloud_signal_;
536 
538  boost::signals2::signal<sig_cb_ensenso_point_cloud_rgb>* point_cloud_rgb_signal_;
539 
541  boost::signals2::signal<sig_cb_ensenso_images>* images_signal_;
542 
544  boost::signals2::signal<sig_cb_ensenso_images_rgb>* images_rgb_signal_;
545 
547  boost::signals2::signal<sig_cb_ensenso_image_depth>* image_depth_signal_;
548 
550  NxLibItem camera_;
551 
552  NxLibItem monocam_;
553 
555  boost::shared_ptr<const NxLibItem> root_;
556 
558  bool use_rgb_;
559 
561  bool find_pattern_;
562 
563 
565  bool device_open_;
566 
568  bool mono_device_open_;
569 
571  bool tcp_open_;
572 
574  Eigen::Affine3d last_pattern_pose_;
575 
577  std::string last_stereo_pattern_;
578 
580  bool store_calibration_pattern_;
581 
583  mutable boost::mutex pattern_mutex_;
584 
586  bool running_;
587 
589  int near_plane_;
590 
592  int far_plane_;
593 
595  float fps_;
596 
598  double timestamp_;
599 
601  Transform tf_left_to_rgb_;
602 
604  mutable boost::mutex fps_mutex_;
605 
613  pcl::uint64_t static getPCLStamp (const double ensenso_stamp);
614 
620  std::string static getOpenCVType (const int channels, const int bpe, const bool isFlt);
621 
627  bool jsonToMatrix (const std::string json, Eigen::Affine3d &matrix) const;
628 
635  bool matrixToJson (const Eigen::Affine3d &matrix, std::string &json, const bool pretty_format=true) const;
636 
640  void processGrabbing ();
641 
645  void triggerCameras();
646 
651  void getImage(const NxLibItem& image_node, pcl::PCLGenImage<pcl::uint8_t>& image_out);
652 
656  void getDepthDataRGB(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& cloud, const pcl::PCLGenImage<float>::Ptr& depthimage);
657 
661  void getDepthData(const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud, const pcl::PCLGenImage<float>::Ptr& depthimage);
662 
663 };
664 } // namespace pcl
665 
666 #endif // __PCL_IO_ENSENSO_GRABBER__
667 
std::vector< T > data
sensor_msgs::PointCloud2 PointCloud
pcl::PointXYZRGBA PointXYZRGBA
std::pair< pcl::PCLGenImage< pcl::uint8_t >, pcl::PCLGenImage< pcl::uint8_t > > PairOfImages
Grabber for IDS-Imaging Ensenso&#39;s devices.
boost::shared_ptr< ::pcl::PCLGenImage< T > const > ConstPtr
pcl::PointXYZ PointXYZ
boost::shared_ptr< ::pcl::PCLGenImage< T > > Ptr


ensenso
Author(s): Francisco Suarez Ruiz
autogenerated on Fri Nov 8 2019 03:45:37