point_cloud_library / 1.12.1 / classpcl_1_1_ensenso_grabber.html /

Grabber for IDS-Imaging Ensenso's devices. More...

#include <pcl/io/ensenso_grabber.h>

Public Member Functions

EnsensoGrabber ()
Constructor. More...
virtual ~EnsensoGrabber () noexcept
Destructor inherited from the Grabber interface. More...
int enumDevices () const
Searches for available devices. More...
bool openDevice (const int device=0)
Opens an Ensenso device. More...
bool closeDevice ()
Closes the Ensenso device. More...
void start ()
Start the point cloud and or image acquisition. More...
void stop ()
Stop the data acquisition. More...
bool isRunning () const
Check if the data acquisition is still running. More...
bool isTcpPortOpen () const
Check if a TCP port is opened. More...
std::string getName () const
Get class name. More...
bool configureCapture (const bool auto_exposure=true, const bool auto_gain=true, const int bining=1, const float exposure=0.32, const bool front_light=false, const int gain=1, const bool gain_boost=false, const bool hardware_gamma=false, const bool hdr=false, const int pixel_clock=10, const bool projector=true, const int target_brightness=80, const std::string trigger_mode="Software", const bool use_disparity_map_area_of_interest=false) const
Configure Ensenso capture settings. More...
bool grabSingleCloud (pcl::PointCloud< pcl::PointXYZ > &cloud) const
Capture a single point cloud and store it. More...
bool initExtrinsicCalibration (const int grid_spacing) const
Set up the Ensenso sensor and API to do 3D extrinsic calibration using the Ensenso 2D patterns. More...
bool clearCalibrationPatternBuffer () const
Clear calibration patterns buffer. More...
int captureCalibrationPattern () const
Captures a calibration pattern. More...
bool estimateCalibrationPatternPose (Eigen::Affine3d &pattern_pose) const
Estimate the calibration pattern pose. More...
bool computeCalibrationMatrix (const std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > &robot_poses, std::string &json, const std::string setup="Moving", const std::string target="Hand", const Eigen::Affine3d &guess_tf=Eigen::Affine3d::Identity(), const bool pretty_format=true) const
Computes the calibration matrix using the collected patterns and the robot poses vector. More...
bool storeEEPROMExtrinsicCalibration () const
Copy the link defined in the Link node of the nxTree to the EEPROM. More...
bool clearEEPROMExtrinsicCalibration ()
Clear the extrinsic calibration stored in the EEPROM by writing an identity matrix. More...
bool setExtrinsicCalibration (const double euler_angle, Eigen::Vector3d &rotation_axis, const Eigen::Vector3d &translation, const std::string target="Hand") const
Update Link node in NxLib tree. More...
bool setExtrinsicCalibration (const std::string target="Hand")
Update Link node in NxLib tree with an identity matrix. More...
bool setExtrinsicCalibration (const Eigen::Affine3d &transformation, const std::string target="Hand")
Update Link node in NxLib tree. More...
float getFramesPerSecond () const
Obtain the number of frames per second (FPS) More...
bool openTcpPort (const int port=24000)
Open TCP port to enable access via the nxTreeEdit program. More...
bool closeTcpPort (void)
Close TCP port program. More...
std::string getTreeAsJson (const bool pretty_format=true) const
Returns the full NxLib tree as a JSON string. More...
std::string getResultAsJson (const bool pretty_format=true) const
Returns the Result node (of the last command) as a JSON string. More...
bool jsonTransformationToEulerAngles (const std::string &json, double &x, double &y, double &z, double &w, double &p, double &r) const
Get the Euler angles corresponding to a JSON string (an angle axis transformation) More...
bool jsonTransformationToAngleAxis (const std::string json, double &alpha, Eigen::Vector3d &axis, Eigen::Vector3d &translation) const
Get the angle axis parameters corresponding to a JSON string. More...
bool jsonTransformationToMatrix (const std::string transformation, Eigen::Affine3d &matrix) const
Get the JSON string corresponding to a 4x4 matrix. More...
bool eulerAnglesTransformationToJson (const double x, const double y, const double z, const double w, const double p, const double r, std::string &json, const bool pretty_format=true) const
Get the JSON string corresponding to the Euler angles transformation. More...
bool angleAxisTransformationToJson (const double x, const double y, const double z, const double rx, const double ry, const double rz, const double alpha, std::string &json, const bool pretty_format=true) const
Get the JSON string corresponding to an angle axis transformation. More...
bool matrixTransformationToJson (const Eigen::Affine3d &matrix, std::string &json, const bool pretty_format=true) const
Get the JSON string corresponding to a 4x4 matrix. More...
- Public Member Functions inherited from pcl::Grabber
Grabber ()=default
Default ctor. More...
Grabber (const Grabber &)=delete
No copy ctor since Grabber can't be copied. More...
Grabber & operator= (const Grabber &)=delete
No copy assign operator since Grabber can't be copied. More...
Grabber (Grabber &&)=default
Move ctor. More...
Grabber & operator= (Grabber &&)=default
Move assign operator. More...
virtual ~Grabber () noexcept=default
virtual destructor. More...
template<typename T >
boost::signals2::connection registerCallback (const std::function< T > &callback)
registers a callback function/method to a signal with the corresponding signature More...
template<typename T >
bool providesCallback () const noexcept
indicates whether a signal with given parameter-type exists or not More...
bool toggle ()
For devices that are streaming, stopped streams are started and running stream are stopped. More...

Public Attributes

shared_ptr< const NxLibItem > root_
Reference to the NxLib tree root. More...
NxLibItem camera_
Reference to the camera tree. More...

Protected Member Functions

void processGrabbing ()
Continuously asks for images and or point clouds data from the device and publishes them if available. More...
- Protected Member Functions inherited from pcl::Grabber
virtual void signalsChanged ()
template<typename T >
boost::signals2::signal< T > * find_signal () const noexcept
template<typename T >
int num_slots () const noexcept
template<typename T >
void disconnect_all_slots ()
template<typename T >
void block_signal ()
template<typename T >
void unblock_signal ()
void block_signals ()
void unblock_signals ()
template<typename T >
boost::signals2::signal< T > * createSignal ()

Static Protected Member Functions

static std::uint64_t getPCLStamp (const double ensenso_stamp)
Convert an Ensenso time stamp into a PCL/ROS time stamp. More...
static std::string getOpenCVType (const int channels, const int bpe, const bool isFlt)
Get OpenCV image type corresponding to the parameters given. More...

Protected Attributes

std::thread grabber_thread_
Grabber thread. More...
boost::signals2::signal< sig_cb_ensenso_point_cloud > * point_cloud_signal_
Boost point cloud signal. More...
boost::signals2::signal< sig_cb_ensenso_images > * images_signal_
Boost images signal. More...
boost::signals2::signal< sig_cb_ensenso_point_cloud_images > * point_cloud_images_signal_
Boost images + point cloud signal. More...
bool device_open_
Whether an Ensenso device is opened or not. More...
bool tcp_open_
Whether an TCP port is opened or not. More...
bool running_
Whether an Ensenso device is running or not. More...
pcl::EventFrequency frequency_
Point cloud capture/processing frequency. More...
std::mutex fps_mutex_
Mutual exclusion for FPS computation. More...
- Protected Attributes inherited from pcl::Grabber
std::map< std::string, std::unique_ptr< boost::signals2::signal_base > > signals_
std::map< std::string, std::vector< boost::signals2::connection > > connections_
std::map< std::string, std::vector< boost::signals2::shared_connection_block > > shared_connections_

Detailed Description

Grabber for IDS-Imaging Ensenso's devices.


The Ensenso SDK allow to use multiple Ensenso devices to produce a single cloud.
This feature is not implemented here, it is up to the user to configure multiple Ensenso cameras.

Author
Victor Lamoine ( victo.nosp@m.r.la.nosp@m.moine.nosp@m.@gma.nosp@m.il.co.nosp@m.m)

Definition at line 66 of file ensenso_grabber.h.

Constructor & Destructor Documentation

EnsensoGrabber()

pcl::EnsensoGrabber::EnsensoGrabber ( )

Constructor.

~EnsensoGrabber()

virtual pcl::EnsensoGrabber::~EnsensoGrabber ( )
virtualnoexcept

Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

angleAxisTransformationToJson()

bool pcl::EnsensoGrabber::angleAxisTransformationToJson ( const double x,
const double y,
const double z,
const double rx,
const double ry,
const double rz,
const double alpha,
std::string & json,
const bool pretty_format = true
) const

Get the JSON string corresponding to an angle axis transformation.

Parameters
[in] x The X angle
[in] y The Y angle
[in] z The Z angle
[in] rx The X component of the Euler axis
[in] ry The Y component of the Euler axis
[in] rz The Z component of the Euler axis
[in] alpha The Euler rotation angle
[out] json A string containing the angle axis transformation in JSON format
[in] pretty_format JSON formatting style
Returns
True if successful, false otherwise
Warning
The units are meters and radians! (the Euler axis doesn't need to be normalized)
Note
See: transformation page in the EnsensoSDK documentation

captureCalibrationPattern()

int pcl::EnsensoGrabber::captureCalibrationPattern ( ) const

Captures a calibration pattern.

Returns
the number of calibration patterns stored in the nxTree, -1 on error
Warning
A device must be opened and must not be running.
Note
You should use initExtrinsicCalibration before

clearCalibrationPatternBuffer()

bool pcl::EnsensoGrabber::clearCalibrationPatternBuffer ( ) const

Clear calibration patterns buffer.

clearEEPROMExtrinsicCalibration()

bool pcl::EnsensoGrabber::clearEEPROMExtrinsicCalibration ( )

Clear the extrinsic calibration stored in the EEPROM by writing an identity matrix.

Returns
True if successful, false otherwise

closeDevice()

bool pcl::EnsensoGrabber::closeDevice ( )

Closes the Ensenso device.

Returns
True if successful, false otherwise

closeTcpPort()

bool pcl::EnsensoGrabber::closeTcpPort ( void )

Close TCP port program.

Returns
True if successful, false otherwise
Warning
If you do not close the TCP port the program might exit with the port still open, if it is the case use
ps -ef
and
kill PID
to kill the application and effectively close the port.

computeCalibrationMatrix()

bool pcl::EnsensoGrabber::computeCalibrationMatrix ( const std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > & robot_poses,
std::string & json,
const std::string setup = "Moving",
const std::string target = "Hand",
const Eigen::Affine3d & guess_tf = Eigen::Affine3d::Identity(),
const bool pretty_format = true
) const

Computes the calibration matrix using the collected patterns and the robot poses vector.

Parameters
[in] robot_poses A list of robot poses, 1 for each pattern acquired (in the same order)
[out] json The extrinsic calibration data in JSON format
[in] setup Moving or Fixed, please refer to the Ensenso documentation
[in] target Please refer to the Ensenso documentation
[in] guess_tf Guess transformation for the calibration matrix (translation in meters)
[in] pretty_format JSON formatting style
Returns
True if successful, false otherwise
Warning
This can take up to 120 seconds
Note
Check the result with getResultAsJson. If you want to permanently store the result, use storeEEPROMExtrinsicCalibration.

configureCapture()

bool pcl::EnsensoGrabber::configureCapture ( const bool auto_exposure = true,
const bool auto_gain = true,
const int bining = 1,
const float exposure = 0.32,
const bool front_light = false,
const int gain = 1,
const bool gain_boost = false,
const bool hardware_gamma = false,
const bool hdr = false,
const int pixel_clock = 10,
const bool projector = true,
const int target_brightness = 80,
const std::string trigger_mode = "Software",
const bool use_disparity_map_area_of_interest = false
) const

Configure Ensenso capture settings.

Parameters
[in] auto_exposure If set to yes, the exposure parameter will be ignored
[in] auto_gain If set to yes, the gain parameter will be ignored
[in] bining Pixel bining: 1, 2 or 4
[in] exposure In milliseconds, from 0.01 to 20 ms
[in] front_light Infrared front light (useful for calibration)
[in] gain Float between 1 and 4
[in] gain_boost
[in] hardware_gamma
[in] hdr High Dynamic Range (check compatibility with other options in Ensenso manual)
[in] pixel_clock In MegaHertz, from 5 to 85
[in] projector Use the central infrared projector or not
[in] target_brightness Between 40 and 210
[in] trigger_mode
[in] use_disparity_map_area_of_interest
Returns
True if successful, false otherwise
Note
See Capture tree item for more details about the parameters.

enumDevices()

int pcl::EnsensoGrabber::enumDevices ( ) const

Searches for available devices.

Returns
The number of Ensenso devices connected

estimateCalibrationPatternPose()

bool pcl::EnsensoGrabber::estimateCalibrationPatternPose ( Eigen::Affine3d & pattern_pose ) const

Estimate the calibration pattern pose.

Parameters
[out] pattern_pose the calibration pattern pose
Returns
true if successful, false otherwise
Warning
A device must be opened and must not be running.
Note
At least one calibration pattern must have been captured before, use captureCalibrationPattern before

eulerAnglesTransformationToJson()

bool pcl::EnsensoGrabber::eulerAnglesTransformationToJson ( const double x,
const double y,
const double z,
const double w,
const double p,
const double r,
std::string & json,
const bool pretty_format = true
) const

Get the JSON string corresponding to the Euler angles transformation.

Parameters
[in] x The X translation
[in] y The Y translation
[in] z The Z translation
[in] w The yaW angle
[in] p The Pitch angle
[in] r The Roll angle
[out] json A string containing the Euler angles transformation in JSON format
[in] pretty_format JSON formatting style
Returns
True if successful, false otherwise
Warning
The units are meters and radians!
Note
See: transformation page in the EnsensoSDK documentation

getFramesPerSecond()

float pcl::EnsensoGrabber::getFramesPerSecond ( ) const
virtual

Obtain the number of frames per second (FPS)

Implements pcl::Grabber.

getName()

std::string pcl::EnsensoGrabber::getName ( ) const
virtual

Get class name.

Returns
A string containing the class name

Implements pcl::Grabber.

getOpenCVType()

static std::string pcl::EnsensoGrabber::getOpenCVType ( const int channels,
const int bpe,
const bool isFlt
)
staticprotected

Get OpenCV image type corresponding to the parameters given.

Parameters
channels number of channels in the image
bpe bytes per element
isFlt is float
Returns
the OpenCV type as a string

getPCLStamp()

static std::uint64_t pcl::EnsensoGrabber::getPCLStamp ( const double ensenso_stamp )
staticprotected

Convert an Ensenso time stamp into a PCL/ROS time stamp.

Parameters
[in] ensenso_stamp
Returns
PCL stamp The Ensenso API returns the time elapsed from January 1st, 1601 (UTC); on Linux OS the reference time is January 1st, 1970 (UTC). See time-stamp page for more info about the time stamp conversion.

getResultAsJson()

std::string pcl::EnsensoGrabber::getResultAsJson ( const bool pretty_format = true ) const

Returns the Result node (of the last command) as a JSON string.

Parameters
[in] pretty_format JSON formatting style
Returns
A string containing the Result node in JSON format

getTreeAsJson()

std::string pcl::EnsensoGrabber::getTreeAsJson ( const bool pretty_format = true ) const

Returns the full NxLib tree as a JSON string.

Parameters
[in] pretty_format JSON formatting style
Returns
A string containing the NxLib tree in JSON format

grabSingleCloud()

bool pcl::EnsensoGrabber::grabSingleCloud ( pcl::PointCloud< pcl::PointXYZ > & cloud ) const

Capture a single point cloud and store it.

Parameters
[out] cloud The cloud to be filled
Returns
True if successful, false otherwise
Warning
A device must be opened and not running

initExtrinsicCalibration()

bool pcl::EnsensoGrabber::initExtrinsicCalibration ( const int grid_spacing ) const

Set up the Ensenso sensor and API to do 3D extrinsic calibration using the Ensenso 2D patterns.

Parameters
[in] grid_spacing
Returns
True if successful, false otherwise

Configures the capture parameters to default values (eg: projector = false and front_light = true) Discards all previous patterns, configures grid_spacing

Warning
A device must be opened and must not be running.
Note
See the Ensenso manual for more information about the extrinsic calibration process.
GridSize item is protected in the NxTree, you can't modify it.

isRunning()

bool pcl::EnsensoGrabber::isRunning ( ) const
virtual

Check if the data acquisition is still running.

Returns
True if running, false otherwise

Implements pcl::Grabber.

isTcpPortOpen()

bool pcl::EnsensoGrabber::isTcpPortOpen ( ) const

Check if a TCP port is opened.

Returns
True if open, false otherwise

jsonTransformationToAngleAxis()

bool pcl::EnsensoGrabber::jsonTransformationToAngleAxis ( const std::string json,
double & alpha,
Eigen::Vector3d & axis,
Eigen::Vector3d & translation
) const

Get the angle axis parameters corresponding to a JSON string.

Parameters
[in] json A string containing the angle axis transformation in JSON format
[out] alpha Euler angle
[out] axis Axis vector
[out] translation Translation vector
Returns
True if successful, false otherwise
Warning
The units are meters and radians!
Note
See: transformation page in the EnsensoSDK documentation

jsonTransformationToEulerAngles()

bool pcl::EnsensoGrabber::jsonTransformationToEulerAngles ( const std::string & json,
double & x,
double & y,
double & z,
double & w,
double & p,
double & r
) const

Get the Euler angles corresponding to a JSON string (an angle axis transformation)

Parameters
[in] json A string containing the angle axis transformation in JSON format
[out] x The X translation
[out] y The Y translation
[out] z The Z translation
[out] w The yaW angle
[out] p The Pitch angle
[out] r The Roll angle
Returns
True if successful, false otherwise
Warning
The units are meters and radians!
Note
See: transformation page in the EnsensoSDK documentation

jsonTransformationToMatrix()

bool pcl::EnsensoGrabber::jsonTransformationToMatrix ( const std::string transformation,
Eigen::Affine3d & matrix
) const

Get the JSON string corresponding to a 4x4 matrix.

Parameters
[in] transformation The input transformation
[out] matrix A matrix containing JSON transformation
Returns
True if successful, false otherwise
Warning
The units are meters and radians!
Note
See: ConvertTransformation page in the EnsensoSDK documentation

matrixTransformationToJson()

bool pcl::EnsensoGrabber::matrixTransformationToJson ( const Eigen::Affine3d & matrix,
std::string & json,
const bool pretty_format = true
) const

Get the JSON string corresponding to a 4x4 matrix.

Parameters
[in] matrix The input matrix
[out] json A string containing the matrix transformation in JSON format
[in] pretty_format JSON formatting style
Returns
True if successful, false otherwise
Warning
The units are meters and radians!
Note
See: ConvertTransformation page in the EnsensoSDK documentation

openDevice()

bool pcl::EnsensoGrabber::openDevice ( const int device = 0 )

Opens an Ensenso device.

Parameters
[in] device The device ID to open
Returns
True if successful, false otherwise

openTcpPort()

bool pcl::EnsensoGrabber::openTcpPort ( const int port = 24000 )

Open TCP port to enable access via the nxTreeEdit program.

Parameters
[in] port The port number
Returns
True if successful, false otherwise

processGrabbing()

void pcl::EnsensoGrabber::processGrabbing ( )
protected

Continuously asks for images and or point clouds data from the device and publishes them if available.

PCL time stamps are filled for both the images and clouds grabbed (see getPCLStamp)

Note
The cloud time stamp is the RAW image time stamp

setExtrinsicCalibration() [1/3]

bool pcl::EnsensoGrabber::setExtrinsicCalibration ( const double euler_angle,
Eigen::Vector3d & rotation_axis,
const Eigen::Vector3d & translation,
const std::string target = "Hand"
) const

Update Link node in NxLib tree.

Parameters
[in] target "Hand" or "Workspace" for example
[in] euler_angle
[in] rotation_axis
[in] translation Translation in meters
Returns
True if successful, false otherwise
Warning
Translation are in meters, rotation angles in radians! (stored in mm/radians in Ensenso tree)
Note
If a calibration has been stored in the EEPROM, it is copied in the Link node at nxLib tree start. This method overwrites the Link node but does not write to the EEPROM.

More information on the parameters can be found in Link node section of the Ensenso manual.

The point cloud you get from the Ensenso is already transformed using this calibration matrix. Make sure it is the identity transformation if you want the original point cloud! (use clearEEPROMExtrinsicCalibration) Use storeEEPROMExtrinsicCalibration to permanently store this transformation

setExtrinsicCalibration() [2/3]

bool pcl::EnsensoGrabber::setExtrinsicCalibration ( const Eigen::Affine3d & transformation,
const std::string target = "Hand"
)

Update Link node in NxLib tree.

Parameters
[in] transformation Transformation matrix
[in] target "Hand" or "Workspace" for example
Returns
True if successful, false otherwise
Warning
Translation are in meters, rotation angles in radians! (stored in mm/radians in Ensenso tree)
Note
If a calibration has been stored in the EEPROM, it is copied in the Link node at nxLib tree start. This method overwrites the Link node but does not write to the EEPROM.

More information on the parameters can be found in Link node section of the Ensenso manual.

The point cloud you get from the Ensenso is already transformed using this calibration matrix. Make sure it is the identity transformation if you want the original point cloud! (use clearEEPROMExtrinsicCalibration) Use storeEEPROMExtrinsicCalibration to permanently store this transformation

setExtrinsicCalibration() [3/3]

bool pcl::EnsensoGrabber::setExtrinsicCalibration ( const std::string target = "Hand" )

Update Link node in NxLib tree with an identity matrix.

Parameters
[in] target "Hand" or "Workspace" for example
Returns
True if successful, false otherwise

start()

void pcl::EnsensoGrabber::start ( )
virtual

Start the point cloud and or image acquisition.

Note
Opens device "0" if no device is open

Implements pcl::Grabber.

stop()

void pcl::EnsensoGrabber::stop ( )
virtual

Stop the data acquisition.

Implements pcl::Grabber.

storeEEPROMExtrinsicCalibration()

bool pcl::EnsensoGrabber::storeEEPROMExtrinsicCalibration ( ) const

Copy the link defined in the Link node of the nxTree to the EEPROM.

Returns
True if successful, false otherwise Refer to setExtrinsicCalibration for more information about how the EEPROM works.
After calling computeCalibrationMatrix, this enables to permanently store the matrix.
Note
The target must be specified ( computeCalibrationMatrix specifies the target)

Member Data Documentation

camera_

NxLibItem pcl::EnsensoGrabber::camera_

Reference to the camera tree.

Warning
You must handle NxLib exceptions manually when playing with camera_ !

Definition at line 430 of file ensenso_grabber.h.

device_open_

bool pcl::EnsensoGrabber::device_open_
protected

Whether an Ensenso device is opened or not.

Definition at line 446 of file ensenso_grabber.h.

fps_mutex_

std::mutex pcl::EnsensoGrabber::fps_mutex_
mutableprotected

Mutual exclusion for FPS computation.

Definition at line 458 of file ensenso_grabber.h.

frequency_

pcl::EventFrequency pcl::EnsensoGrabber::frequency_
protected

Point cloud capture/processing frequency.

Definition at line 455 of file ensenso_grabber.h.

grabber_thread_

std::thread pcl::EnsensoGrabber::grabber_thread_
protected

Grabber thread.

Definition at line 434 of file ensenso_grabber.h.

images_signal_

boost::signals2::signal<sig_cb_ensenso_images>* pcl::EnsensoGrabber::images_signal_
protected

Boost images signal.

Definition at line 440 of file ensenso_grabber.h.

point_cloud_images_signal_

boost::signals2::signal<sig_cb_ensenso_point_cloud_images>* pcl::EnsensoGrabber::point_cloud_images_signal_
protected

Boost images + point cloud signal.

Definition at line 443 of file ensenso_grabber.h.

point_cloud_signal_

boost::signals2::signal<sig_cb_ensenso_point_cloud>* pcl::EnsensoGrabber::point_cloud_signal_
protected

Boost point cloud signal.

Definition at line 437 of file ensenso_grabber.h.

root_

shared_ptr<const NxLibItem> pcl::EnsensoGrabber::root_

Reference to the NxLib tree root.

Warning
You must handle NxLib exceptions manually when playing with root_ ! See ensensoExceptionHandling in ensenso_grabber.cpp

Definition at line 426 of file ensenso_grabber.h.

running_

bool pcl::EnsensoGrabber::running_
protected

Whether an Ensenso device is running or not.

Definition at line 452 of file ensenso_grabber.h.

tcp_open_

bool pcl::EnsensoGrabber::tcp_open_
protected

Whether an TCP port is opened or not.

Definition at line 449 of file ensenso_grabber.h.


The documentation for this class was generated from the following file:

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_ensenso_grabber.html