39 #include <pcl/pcl_config.h> 41 #ifndef __PCL_IO_ENSENSO_GRABBER__ 42 #define __PCL_IO_ENSENSO_GRABBER__ 45 #include <pcl/common/io.h> 46 #include <pcl/io/eigen.h> 47 #include <Eigen/Geometry> 48 #include <Eigen/StdVector> 49 #include <pcl/io/boost.h> 50 #include <boost/thread.hpp> 51 #include <boost/lexical_cast.hpp> 53 #include <pcl/io/grabber.h> 54 #include <pcl/common/synchronizer.h> 71 typedef std::pair<pcl::PCLImage, pcl::PCLImage> PairOfImages;
75 typedef boost::shared_ptr<EnsensoGrabber> Ptr;
76 typedef boost::shared_ptr<const EnsensoGrabber> ConstPtr;
83 (sig_cb_ensenso_images) (
const boost::shared_ptr<PairOfImages> &);
87 const boost::shared_ptr<PairOfImages> &);
100 enumDevices ()
const;
106 openDevice (
const int device = 0);
130 isTcpPortOpen ()
const;
156 configureCapture (
const bool auto_exposure =
true,
157 const bool auto_gain =
true,
158 const int bining = 1,
159 const float exposure = 0.32,
160 const bool front_light =
false,
162 const bool gain_boost =
false,
163 const bool hardware_gamma =
false,
164 const bool hdr =
false,
165 const int pixel_clock = 10,
166 const bool projector =
true,
167 const int target_brightness = 80,
168 const std::string trigger_mode =
"Software",
169 const bool use_disparity_map_area_of_interest =
false)
const;
190 initExtrinsicCalibration (
const int grid_spacing)
const;
194 clearCalibrationPatternBuffer ()
const;
201 captureCalibrationPattern ()
const;
209 estimateCalibrationPatternPose (Eigen::Affine3d &pattern_pose)
const;
223 computeCalibrationMatrix (
const std::vector<Eigen::Affine3d, Eigen::aligned_allocator<Eigen::Affine3d> > &robot_poses,
225 const std::string setup =
"Moving",
226 const std::string target =
"Hand",
227 const Eigen::Affine3d &guess_tf = Eigen::Affine3d::Identity (),
228 const bool pretty_format =
true)
const;
236 storeEEPROMExtrinsicCalibration ()
const;
241 clearEEPROMExtrinsicCalibration ();
260 setExtrinsicCalibration (
const double euler_angle,
261 Eigen::Vector3d &rotation_axis,
262 const Eigen::Vector3d &translation,
263 const std::string target =
"Hand");
269 setExtrinsicCalibration (
const std::string target =
"Hand");
286 setExtrinsicCalibration (
const Eigen::Affine3d &transformation,
287 const std::string target =
"Hand");
291 getFramesPerSecond ()
const;
297 openTcpPort (
const int port = 24000);
310 getTreeAsJson (
const bool pretty_format =
true)
const;
317 getResultAsJson (
const bool pretty_format =
true)
const;
332 jsonTransformationToEulerAngles (
const std::string &json,
350 jsonTransformationToAngleAxis (
const std::string json,
352 Eigen::Vector3d &axis,
353 Eigen::Vector3d &translation)
const;
364 jsonTransformationToMatrix (
const std::string transformation,
365 Eigen::Affine3d &matrix)
const;
382 eulerAnglesTransformationToJson (
const double x,
389 const bool pretty_format =
true)
const;
406 angleAxisTransformationToJson (
const double x,
414 const bool pretty_format =
true)
const;
425 matrixTransformationToJson (
const Eigen::Affine3d &matrix,
427 const bool pretty_format =
true)
const;
432 boost::shared_ptr<const NxLibItem>
root_;
473 getPCLStamp (
const double ensenso_stamp);
482 getOpenCVType (
const int channels,
494 #endif // __PCL_IO_ENSENSO_GRABBER__ boost::signals2::signal< sig_cb_ensenso_images > * images_signal_
Boost images signal.
pcl::EventFrequency frequency_
Point cloud capture/processing frequency.
boost::signals2::signal< sig_cb_ensenso_point_cloud_images > * point_cloud_images_signal_
Boost images + point cloud signal.
This file defines compatibility wrappers for low level I/O functions.
bool device_open_
Whether an Ensenso device is opened or not.
NxLibItem camera_
Reference to the camera tree.
A helper class to measure frequency of a certain event.
Grabber interface for PCL 1.x device drivers.
bool tcp_open_
Whether an TCP port is opened or not.
boost::shared_ptr< PointCloud< PointT > > Ptr
boost::thread grabber_thread_
Grabber thread.
boost::signals2::signal< sig_cb_ensenso_point_cloud > * point_cloud_signal_
Boost point cloud signal.
bool running_
Whether an Ensenso device is running or not.
PointCloud represents the base class in PCL for storing collections of 3D points.
boost::shared_ptr< const NxLibItem > root_
Reference to the NxLib tree root.
Grabber for IDS-Imaging Ensenso's devices.
boost::mutex fps_mutex_
Mutual exclusion for FPS computation.
Define methods for measuring time spent in code blocks.