41 #include <pcl/pcl_config.h>
44 #include <pcl/common/io.h>
45 #include <pcl/io/eigen.h>
46 #include <Eigen/Geometry>
47 #include <Eigen/StdVector>
48 #include <pcl/io/boost.h>
50 #include <pcl/io/grabber.h>
51 #include <pcl/common/synchronizer.h>
70 using PairOfImages = std::pair<pcl::PCLImage, pcl::PCLImage>;
74 using Ptr = shared_ptr<EnsensoGrabber>;
75 using ConstPtr = shared_ptr<const EnsensoGrabber>;
80 using sig_cb_ensenso_images = void(
const shared_ptr<PairOfImages>&);
102 openDevice (const
int device = 0);
126 isTcpPortOpen () const;
152 configureCapture (const
bool auto_exposure = true,
153 const
bool auto_gain = true,
154 const
int bining = 1,
155 const
float exposure = 0.32,
156 const
bool front_light = false,
158 const
bool gain_boost = false,
159 const
bool hardware_gamma = false,
160 const
bool hdr = false,
161 const
int pixel_clock = 10,
162 const
bool projector = true,
163 const
int target_brightness = 80,
164 const std::
string trigger_mode = "Software",
165 const
bool use_disparity_map_area_of_interest = false) const;
186 initExtrinsicCalibration (const
int grid_spacing) const;
190 clearCalibrationPatternBuffer () const;
197 captureCalibrationPattern () const;
205 estimateCalibrationPatternPose (
Eigen::Affine3d &pattern_pose) const;
219 computeCalibrationMatrix (const std::vector<
Eigen::Affine3d,
Eigen::aligned_allocator<
Eigen::Affine3d> > &robot_poses,
221 const std::
string setup = "Moving",
222 const std::
string target = "Hand",
223 const
Eigen::Affine3d &guess_tf =
Eigen::Affine3d::Identity (),
224 const
bool pretty_format = true) const;
232 storeEEPROMExtrinsicCalibration () const;
237 clearEEPROMExtrinsicCalibration ();
256 setExtrinsicCalibration (const
double euler_angle,
257 Eigen::Vector3d &rotation_axis,
258 const
Eigen::Vector3d &translation,
259 const std::
string target = "Hand") const;
265 setExtrinsicCalibration (const std::
string target = "Hand");
282 setExtrinsicCalibration (const
Eigen::Affine3d &transformation,
283 const std::
string target = "Hand");
287 getFramesPerSecond () const;
293 openTcpPort (const
int port = 24000);
306 getTreeAsJson (const
bool pretty_format = true) const;
313 getResultAsJson (const
bool pretty_format = true) const;
328 jsonTransformationToEulerAngles (const std::
string &json,
346 jsonTransformationToAngleAxis (const std::
string json,
348 Eigen::Vector3d &axis,
349 Eigen::Vector3d &translation) const;
360 jsonTransformationToMatrix (const std::
string transformation,
361 Eigen::Affine3d &matrix) const;
378 eulerAnglesTransformationToJson (const
double x,
385 const
bool pretty_format = true) const;
402 angleAxisTransformationToJson (const
double x,
410 const
bool pretty_format = true) const;
421 matrixTransformationToJson (const
Eigen::Affine3d &matrix,
423 const
bool pretty_format = true) const;
428 shared_ptr<const NxLibItem> root_;
436 std::thread grabber_thread_;
439 boost::signals2::signal<sig_cb_ensenso_point_cloud>* point_cloud_signal_;
442 boost::signals2::signal<sig_cb_ensenso_images>* images_signal_;
445 boost::signals2::signal<sig_cb_ensenso_point_cloud_images>* point_cloud_images_signal_;
460 mutable std::mutex fps_mutex_;
469 getPCLStamp (const
double ensenso_stamp);
478 getOpenCVType (const
int channels,
Grabber for IDS-Imaging Ensenso's devices.
virtual ~EnsensoGrabber() noexcept
Destructor inherited from the Grabber interface.
EnsensoGrabber()
Constructor.
A helper class to measure frequency of a certain event.
Grabber interface for PCL 1.x device drivers.
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
Define methods for measuring time spent in code blocks.
A point structure representing Euclidean xyz coordinates.