Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Types | List of all members
pcl::EnsensoGrabber Class Reference

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

#include <ensenso_grabber.h>

Inheritance diagram for pcl::EnsensoGrabber:
Inheritance graph
[legend]

Public Member Functions

bool calibrateHandEye (const std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > &robot_poses, const Eigen::Affine3d &camera_seed, const Eigen::Affine3d &pattern_seed, const std::string setup, Eigen::Affine3d &estimated_camera_pose, Eigen::Affine3d &estimated_pattern_pose, int &iterations, double &reprojection_error) const
 With this command you can calibrate the position of the camera with respect to a robot. The calibration routine currently supports two types of setups: either your camera is fixed with respect to the robot origin, or your camera mounted on the robot hand and is moving with the robot. More...
 
bool closeDevices ()
 Closes all Ensenso devices. More...
 
bool closeTcpPort (void)
 Close TCP port program. More...
 
int collectPattern (const bool buffer=true) const
 Collects a calibration pattern. More...
 
double decodePattern () const
 Decodes the pattern grid size and thickness. More...
 
bool discardPatterns () const
 Clears the pattern buffers of monocular and stereo pattern observations. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EnsensoGrabber ()
 Constructor. More...
 
int enumDevices () const
 Searches for available devices. More...
 
bool estimatePatternPose (Eigen::Affine3d &pose, const bool average=false) const
 Estimate the calibration pattern pose. More...
 
bool getCameraInfo (std::string cam, sensor_msgs::CameraInfo &cam_info) const
 Get meta information for a monocular camera. More...
 
float getFramesPerSecond () const
 Obtain the number of frames per second (FPS) More...
 
bool getLastCalibrationPattern (std::vector< int > &grid_size, double &grid_spacing, std::vector< Eigen::Vector2d > &left_points, std::vector< Eigen::Vector2d > &right_points, Eigen::Affine3d &pose) const
 Get the raw stereo pattern information and the pattern pose. Before using it enable the storeCalibrationPattern. More...
 
std::string getName () const
 Get class name. More...
 
int getPatternCount () const
 Gets the number of collected patterns with successful observations in two cameras. More...
 
bool getTFLeftToRGB (Transform &tf) const
 Get transformation between stereo frame and rgb frame. More...
 
bool grabSingleCloud (pcl::PointCloud< pcl::PointXYZ > &cloud)
 Capture a single point cloud and store it. More...
 
bool isRunning () const
 Check if the data acquisition is still running. More...
 
bool isTcpPortOpen () const
 Check if a TCP port is opened. More...
 
bool openDevice (std::string serial)
 Opens an Ensenso device. More...
 
bool openMonoDevice (std::string serial)
 Opens an Ensenso mono device. More...
 
bool openTcpPort (const int port=24000)
 Open TCP port to enable access via the nxTreeEdit program. More...
 
bool restoreDefaultConfiguration () const
 Restores the default capture configuration parameters. More...
 
bool setAutoBlackLevel (const bool enable=true) const
 Controls whether the sensor black level should be adjusted automatically by the image sensor. More...
 
bool setAutoExposure (const bool enable=true) const
 Controls whether the exposure should be adjusted after each image capture. More...
 
bool setAutoGain (const bool enable=true) const
 Controls whether the gain should be adjusted after each image capture. More...
 
bool setBinning (const int binning=1) const
 Adjusts the camera's binning factor. Binning reduces the image resolution by an integer factor directly on the sensor, and thus greatly reduces the image transfer times. Changing this node's value directly reduces the resolution of all binary image nodes accordingly. More...
 
bool setBlackLevelOffset (const float offset=1.0) const
 The current black level offset. When AutoBlackLevel is false this value specifies the sensor black level directly, otherwise the offset is applied on top of the automatically estimated sensor black level. More...
 
bool setDepthChangeCost (const int changecost) const
 The penalty for changes of +/- 1 disparity along an optimization path. Setting a larger value for DepthChangeCost will result in smoother surfaces, but some details might get lost when setting this value too large. More...
 
bool setDepthStepCost (const int stepcost) const
 The penalty for steps (changes of more than one disparity) along an optimization path. Setting a larger value for DepthStepCost will yield better detection of planar surfaces in low contrast areas, but too large values will lead to a loss of geometry details and precise object boundaries. More...
 
bool setEnableCUDA (const bool enable=true) const
 Enables CUDA support. More...
 
bool setExposure (const float exposure=1.0) const
 The current image exposure time. More...
 
bool setFarPlane (const int far)
 Specifies the maximum distance to the ViewPose below which surface elements will be excluded from the depth map. More...
 
bool setFillBorderSpread (const int maximumspread) const
 Defines which missing regions will be filled by setting a threshold on the maximum spread of the disparities on the region boundary. Setting this value reasonably small will ensure that only missing patches inside planar faces will be filled whereas gaps at depth discontinuities are kept unfilled. More...
 
bool setFillRegionSize (const int regionsize) const
 Defines an upper limit on the region size in pixels, up to which a region is accepted for filling. The region must also satisfy the BorderSpread condition to be filled. More...
 
bool setFindPattern (const bool enable=true)
 Controls, whether the grabber will try finding the pattern in the scene. More...
 
bool setFlexView (const bool enable=false, const int imagepairs=2) const
 The number of image pairs to capture. When FlexView is set to false the camera will operate in normal one-shot stereo mode. If FlexView is enabled the Capture command will automatically capture the indicated number of image pairs and shift the projectors pattern between each exposure. All image pairs will then be used to compute depth data in ComputeDisparityMap. Using more than one image pair will increase the effective X, Y and Z resolution. More...
 
bool setFrontLight (const bool enable=false) const
 Enables the diffuse front light during exposure. This should only be used when calibrating or tracking a calibration pattern. Please also note the illumination limitations. More...
 
bool setGain (const float gain=1.0) const
 The current analog gain factor. See also MaxGain. More...
 
bool setGainBoost (const bool enable=false) const
 Enables the cameras analog gain boost function. More...
 
bool setGridSpacing (const double grid_spacing) const
 Sets the grid spacing of the calibration pattern. More...
 
bool setHardwareGamma (const bool enable=true) const
 Enables the camera's internal analog gamma correction. This boosts dark pixels while compressing higher brightness values. More...
 
bool setHdr (const bool enable=false) const
 Enables the camera's high dynamic range function with a fixed, piece-wise linear response curve. More...
 
bool setMedianFilterRadius (const int radius) const
 Specifies the size of the median filter as radius in pixels, excluding the center pixel. The filter is applied to the disparity map. Median filtering will reduce noise inside surfaces while maintaining sharp edges, but object corners will be rounded. More...
 
bool setMinimumDisparity (const int disparity=-64) const
 The minimum disparity in pixels where correspondences in the stereo image pair are being searched. The resolution reductions by Scaling and Binning are automatically accounted for. The actual value used in the matching process is output in ScaledMinimumDisparity. More...
 
bool setNearPlane (const int near)
 Specifies the minimum distance to the ViewPose below which surface elements will be excluded from the depth map. More...
 
bool setNumberOfDisparities (const int number=128) const
 The number of disparities in pixels where correspondences in the stereo image pair are being searched, starting at MinDisparity. The resolution reductions by Scaling and Binning are automatically accounted for. The actual value used in the matching process is output in ScaledNumberOfDisparities. More...
 
bool setOptimizationProfile (const std::string profile="AlignedAndDiagonal") const
 The type of Semi-Global-Matching optimization carried out on the cost function. More...
 
bool setPixelClock (const int pixel_clock=24) const
 Sets the pixel clock in MHz. If you have too many devices on the same bus the image transfer might fail when the clock is too high. This happens when the host PC does not request data from the camera fast enough. The sensor then outputs data faster than it can be transferred to the host and the cameras buffer will overflow. Thus the image transfer is incomplete and the image is lost. More...
 
bool setProjector (const bool enable=true) const
 Enables the texture projector during exposure. This should only be used for depth map computation. Please also note the illumination limitations. More...
 
bool setRGBTriggerDelay (const float delay=10) const
 The delay between trigger of the stereo camera (and projector) and the RGB camera. More...
 
bool setScaling (const float scaling=1.0) const
 Scaling allows to reduce the camera resolution by an arbitrary non-integer factor during rectification. The camera raw images stay at their original size, but the rectified images, DisparityMap and PointMap will be scaled by the specified factor to improve stereo matching runtime. This allows you to choose you own tradeoff between image resolution and performance. More...
 
bool setShadowingThreshold (const int shadowingthreshold) const
 The disparity map is checked for occluded pixels. This is usually called 'left-right consistency check'. A pixel is only accepted if it is a mutually best match with the assigned right image pixel. Due to subpixel interpolation and half-occluded pixels, it is reasonable to allow small deviations from 'exact mutual' matches. This threshold sets the allowed range of mismatch in pixels. More...
 
bool setSpeckleComponentThreshold (const int threshold) const
 Defines how the image is divided into regions for speckle filtering. Whenever two neighboring pixel disparities differ by more than ComponentThreshold disparities, the two pixels are considered as belonging to separate regions. Consequently, each resulting region will not have discontinuities larger or equal to ComponentThreshold in it's disparity map area. More...
 
bool setSpeckleRegionSize (const int threshold) const
 The size in pixels of a disparity map region below which the region will be removed from the disparity map. The computation of the regions is controlled by ComponentThreshold. More...
 
bool setSurfaceConnectivity (const int threshold) const
 The distance along a camera's z direction below which two neighboring points will be connected to a surface triangle. More...
 
bool setTargetBrightness (const int target=80) const
 The desired average image brightness in gray values used for AutoExposure and AutoGain. More...
 
bool setTriggerMode (const std::string mode="Software") const
 Specifies how an image capture is initiated. More...
 
bool setUniquenessRatio (const int ratio) const
 Filters the pixels depending on the uniqueness of the found correspondence. The value indicates the percentage, by which the cost of the next best correspondence must be larger (compared to the best correspondence), such that the pixel is accepted. More...
 
bool setUseDisparityMapAreaOfInterest (const bool enable=false) const
 Reduces the camera's capture AOI to the region necessary for the currently set stereo matching AOI. This will reduce the image transfer time, especially when setting smaller AOIs for the stereo matching. More...
 
bool setUseOpenGL (const bool enable) const
 Configures the use of OpenGL. More...
 
bool setUseRGB (const bool enable=true)
 Controls, whether the grabber will use an external ensenso rgb camera. More...
 
void start ()
 Start the point cloud and or image acquisition. More...
 
void stop ()
 Stop the data acquisition. More...
 
void storeCalibrationPattern (const bool enable)
 Enables collecting the calibration pattern continuous during processGrabbing() More...
 
virtual ~EnsensoGrabber () throw ()
 Destructor inherited from the Grabber interface. It never throws. More...
 

Protected Member Functions

void getDepthData (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::PCLGenImage< float >::Ptr &depthimage)
 Retrieve depth data from NxLib. More...
 
void getDepthDataRGB (const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &cloud, const pcl::PCLGenImage< float >::Ptr &depthimage)
 Retrieve RGB depth data from NxLib. More...
 
void getImage (const NxLibItem &image_node, pcl::PCLGenImage< pcl::uint8_t > &image_out)
 Retrieve Image from NxLib. More...
 
bool jsonToMatrix (const std::string json, Eigen::Affine3d &matrix) const
 Converts a JSON string into an Eigen::Affine3d. More...
 
bool matrixToJson (const Eigen::Affine3d &matrix, std::string &json, const bool pretty_format=true) const
 Converts an Eigen::Affine3d into a JSON string transformation (4x4) More...
 
void processGrabbing ()
 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) More...
 
void triggerCameras ()
 triggers all available cameras More...
 

Static Protected Member Functions

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

Protected Attributes

NxLibItem camera_
 References to the camera tree. More...
 
bool device_open_
 Whether an Ensenso device is opened or not. More...
 
int far_plane_
 Far plane Parameter for the RenderPointMap command. More...
 
bool find_pattern_
 Whether the grabber tries to find the pattern or not. More...
 
float fps_
 Camera frames per second (FPS) More...
 
boost::mutex fps_mutex_
 Mutual exclusion for FPS computation. More...
 
boost::thread grabber_thread_
 Grabber thread. More...
 
boost::signals2::signal< sig_cb_ensenso_image_depth > * image_depth_signal_
 Boost depth image signal. More...
 
boost::signals2::signal< sig_cb_ensenso_images_rgb > * images_rgb_signal_
 Boost images rgb signal. More...
 
boost::signals2::signal< sig_cb_ensenso_images > * images_signal_
 Boost images signal. More...
 
Eigen::Affine3d last_pattern_pose_
 Last pose of the detected pattern during processGrabbing() More...
 
std::string last_stereo_pattern_
 Last raw stereo info of the detected pattern during processGrabbing() More...
 
bool mono_device_open_
 Whether an Ensenso device is opened or not. More...
 
NxLibItem monocam_
 
int near_plane_
 Near plane Parameter for the RenderPointMap command. More...
 
boost::mutex pattern_mutex_
 Mutual exclusion for reading pattern pose. More...
 
boost::signals2::signal< sig_cb_ensenso_point_cloud_rgb > * point_cloud_rgb_signal_
 Boost point cloud signal with RGB. More...
 
boost::signals2::signal< sig_cb_ensenso_point_cloud > * point_cloud_signal_
 Boost point cloud signal. More...
 
boost::shared_ptr< const NxLibItem > root_
 Reference to the NxLib tree root. More...
 
bool running_
 Whether an Ensenso device is running or not. More...
 
bool store_calibration_pattern_
 Whether to read the pattern pose at processGrabbing() or not. More...
 
bool tcp_open_
 Whether an TCP port is opened or not. More...
 
Transform tf_left_to_rgb_
 translation from left camera to RGB frame More...
 
double timestamp_
 timestamp of the current frame More...
 
bool use_rgb_
 Whether the grabber uses RGB or not. More...
 

Private Types

typedef std::pair< pcl::PCLGenImage< pcl::uint8_t >, pcl::PCLGenImage< pcl::uint8_t > > PairOfImages
 

Detailed Description

Grabber for IDS-Imaging Ensenso's devices.

Author
Francisco Suarez-Ruiz

Definition at line 37 of file ensenso_grabber.h.

Member Typedef Documentation

typedef std::pair<pcl::PCLGenImage<pcl::uint8_t>, pcl::PCLGenImage<pcl::uint8_t> > pcl::EnsensoGrabber::PairOfImages
private

Definition at line 39 of file ensenso_grabber.h.

Constructor & Destructor Documentation

pcl::EnsensoGrabber::EnsensoGrabber ( )

Constructor.

Definition at line 17 of file ensenso_grabber.cpp.

pcl::EnsensoGrabber::~EnsensoGrabber ( )
throw (
)
virtual

Destructor inherited from the Grabber interface. It never throws.

Definition at line 45 of file ensenso_grabber.cpp.

Member Function Documentation

bool pcl::EnsensoGrabber::calibrateHandEye ( const std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > &  robot_poses,
const Eigen::Affine3d &  camera_seed,
const Eigen::Affine3d &  pattern_seed,
const std::string  setup,
Eigen::Affine3d &  estimated_camera_pose,
Eigen::Affine3d &  estimated_pattern_pose,
int &  iterations,
double &  reprojection_error 
) const

With this command you can calibrate the position of the camera with respect to a robot. The calibration routine currently supports two types of setups: either your camera is fixed with respect to the robot origin, or your camera mounted on the robot hand and is moving with the robot.

Parameters
[in]robot_posesA list of robot poses, 1 for each pattern acquired (in the same order)
[in]camera_seedInitial guess of the camera pose. The pose must be given relative to the robot hand (for a moving camera setup), or relative to the robot origin (for the fixed camera setup).
[in]pattern_seedInitial guess of the pattern pose. This pose must be given relative to the robot hand (for a fixed camera setup), or relative to the robot origin (for the moving camera setup).
[in]setupMoving or Fixed, please refer to the Ensenso documentation
[out]estimated_camera_poseThe Transformation between this camera's left eye coordinates and the next linked system.
[out]estimated_pattern_poseThe estimated pattern pose. This pose is either relative to the robot hand (for a fixed camera setup), or relative to the robot origin (for the moving camera setup).
[out]iterationsIndicates the number of optimization iterations performed on the final solution until it had converged.
[out]reprojection_errorThe reprojection error per pattern point over all collected patterns of the final solution.
Returns
True if successful, false otherwise
Warning
This can take up to 120 seconds

Definition at line 68 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::closeDevices ( )

Closes all Ensenso devices.

Returns
True if successful, false otherwise

Definition at line 158 of file ensenso_grabber.cpp.

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.

Definition at line 180 of file ensenso_grabber.cpp.

int pcl::EnsensoGrabber::collectPattern ( const bool  buffer = true) const

Collects a calibration pattern.

Parameters
[in]bufferSpecifies whether the pattern should be added to the pattern buffer.
Returns
the number of calibration patterns stored in the
nxTree
, -1 on error
Warning
A device must be opened and must not be running.

Definition at line 195 of file ensenso_grabber.cpp.

double pcl::EnsensoGrabber::decodePattern ( ) const

Decodes the pattern grid size and thickness.

Returns
the grid size in mm

Definition at line 215 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::discardPatterns ( ) const

Clears the pattern buffers of monocular and stereo pattern observations.

Returns
True if successful, false otherwise
Note
The counters PatternCount and MonocularPatternCount will be zero after clearing.

Definition at line 237 of file ensenso_grabber.cpp.

int pcl::EnsensoGrabber::enumDevices ( ) const

Searches for available devices.

Returns
The number of Ensenso devices connected

Definition at line 272 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::estimatePatternPose ( Eigen::Affine3d &  pose,
const bool  average = false 
) const

Estimate the calibration pattern pose.

Parameters
[out]posethe calibration pattern pose
[in]averageSpecifies if all pattern point coordinates in the buffer should be averaged to produce a more precise pose measurement. This will only produce a correct result if all patterns in the buffer originate from multiple images of the same pattern in the same 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 collected before, use collectPattern() before

Definition at line 251 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::getCameraInfo ( std::string  cam,
sensor_msgs::CameraInfo &  cam_info 
) const

Get meta information for a monocular camera.

Parameters
[in]camA string containing the camera (Left or Right)
[out]cam_infometa information for a camera.
Returns
True if successful, false otherwise
Note
See: sensor_msgs/CameraInfo

Definition at line 297 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::getDepthData ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  cloud,
const pcl::PCLGenImage< float >::Ptr &  depthimage 
)
protected

Retrieve depth data from NxLib.

Parameters
[out]acquiredpoint cloud and depth image

Definition at line 914 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::getDepthDataRGB ( const pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &  cloud,
const pcl::PCLGenImage< float >::Ptr &  depthimage 
)
protected

Retrieve RGB depth data from NxLib.

Parameters
[out]acquiredpoint cloud and depth image

Definition at line 855 of file ensenso_grabber.cpp.

float pcl::EnsensoGrabber::getFramesPerSecond ( ) const

Obtain the number of frames per second (FPS)

Definition at line 461 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::getImage ( const NxLibItem &  image_node,
pcl::PCLGenImage< pcl::uint8_t > &  image_out 
)
protected

Retrieve Image from NxLib.

Parameters
[out]acquiredimage
[in]NxLibNode from which image should be acquired

Definition at line 980 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::getLastCalibrationPattern ( std::vector< int > &  grid_size,
double &  grid_spacing,
std::vector< Eigen::Vector2d > &  left_points,
std::vector< Eigen::Vector2d > &  right_points,
Eigen::Affine3d &  pose 
) const

Get the raw stereo pattern information and the pattern pose. Before using it enable the storeCalibrationPattern.

Parameters
[out]grid_sizeThe number of points on the patterns grid as two element vector.
[out]grid_spacingDistance of two neighboring grid points along this pattern's x or y axis.
[out]left_pointsthe raw image positions of the pattern dots in the first camera.
[out]right_pointsthe raw image dot positions in the second camera.
[out]posethe calibration pattern pose.
Returns
True if successful, false otherwise

Definition at line 425 of file ensenso_grabber.cpp.

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

Get class name.

Returns
A string containing the class name

Definition at line 467 of file ensenso_grabber.cpp.

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
channelsnumber of channels in the image
bpebytes per element
isFltis float
Returns
the OpenCV type as a string

Definition at line 472 of file ensenso_grabber.cpp.

int pcl::EnsensoGrabber::getPatternCount ( ) const

Gets the number of collected patterns with successful observations in two cameras.

Returns
The number of pattern in the camera buffer

Definition at line 490 of file ensenso_grabber.cpp.

pcl::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.

Definition at line 481 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::getTFLeftToRGB ( Transform tf) const

Get transformation between stereo frame and rgb frame.

Returns
True if successful, false otherwise

Definition at line 385 of file ensenso_grabber.cpp.

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

Capture a single point cloud and store it.

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

Definition at line 495 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::isRunning ( ) const

Check if the data acquisition is still running.

Returns
True if running, false otherwise

Definition at line 539 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::isTcpPortOpen ( ) const

Check if a TCP port is opened.

Returns
True if open, false otherwise

Definition at line 544 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::jsonToMatrix ( const std::string  json,
Eigen::Affine3d &  matrix 
) const
protected

Converts a JSON string into an Eigen::Affine3d.

Parameters
[in]jsonThe input JSON transformation
[out]matrixAn Eigen matrix containing the resulting transformation
Returns
True if successful, false otherwise

Definition at line 549 of file ensenso_grabber.cpp.

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

Converts an Eigen::Affine3d into a JSON string transformation (4x4)

Parameters
[in]matrixAn Eigen matrix
[out]jsonThe output JSON transformation
[in]pretty_formatJSON formatting style
Returns
True if successful, false otherwise

Definition at line 581 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::openDevice ( std::string  serial)

Opens an Ensenso device.

Parameters
[in]serialThe camera serial
Returns
True if successful, false otherwise

Definition at line 616 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::openMonoDevice ( std::string  serial)

Opens an Ensenso mono device.

Parameters
[in]serialThe camera serial
Returns
True if successful, false otherwise

Definition at line 642 of file ensenso_grabber.cpp.

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

Open TCP port to enable access via the nxTreeEdit program.

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

Definition at line 668 of file ensenso_grabber.cpp.

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

Definition at line 683 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::restoreDefaultConfiguration ( ) const

Restores the default capture configuration parameters.

Returns
True if successful, false otherwise

Definition at line 1000 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setAutoBlackLevel ( const bool  enable = true) const

Controls whether the sensor black level should be adjusted automatically by the image sensor.

Parameters
[in]enableWhen set to true the image sensor black level will be adjusted automatically.
Returns
True if successful, false otherwise

Definition at line 1061 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setAutoExposure ( const bool  enable = true) const

Controls whether the exposure should be adjusted after each image capture.

Parameters
[in]enableWhen set to true the Exposure will be adjusted after each Capture command involving this camera.
Returns
True if successful, false otherwise

Definition at line 1077 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setAutoGain ( const bool  enable = true) const

Controls whether the gain should be adjusted after each image capture.

Parameters
[in]enableWhen set to true the Gain will be adjusted after each Capture command involving this camera.
Returns
True if successful, false otherwise

Definition at line 1093 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setBinning ( const int  binning = 1) const

Adjusts the camera's binning factor. Binning reduces the image resolution by an integer factor directly on the sensor, and thus greatly reduces the image transfer times. Changing this node's value directly reduces the resolution of all binary image nodes accordingly.

Parameters
[in]binningA positive integer specifying the binning factor.
Returns
True if successful, false otherwise
Note
Changing the binning factor cancels any running capture operation and clears all images for the corresponding camera.

Definition at line 1109 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setBlackLevelOffset ( const float  offset = 1.0) const

The current black level offset. When AutoBlackLevel is false this value specifies the sensor black level directly, otherwise the offset is applied on top of the automatically estimated sensor black level.

Parameters
[in]offsetA number between 0.0 and 1.0. Values closer to zero will yield darker images, values closer to one will increase the image brightness at the expense of noise in dark image regions.
Returns
True if successful, false otherwise

Definition at line 1126 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setDepthChangeCost ( const int  changecost) const

The penalty for changes of +/- 1 disparity along an optimization path. Setting a larger value for DepthChangeCost will result in smoother surfaces, but some details might get lost when setting this value too large.

Parameters
[in]changecostA positive integer specifying the cost of disparity changes in the disparity map.
Note
his value must be smaller than DepthStepCost. Default Value 5

Definition at line 1459 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setDepthStepCost ( const int  stepcost) const

The penalty for steps (changes of more than one disparity) along an optimization path. Setting a larger value for DepthStepCost will yield better detection of planar surfaces in low contrast areas, but too large values will lead to a loss of geometry details and precise object boundaries.

Parameters
[in]stepcostA positive integer, strictly larger than DepthChangeCost, specifying the cost of disparity steps (discontinuities) in the disparity map.
Note
This value must be larger than DepthChangeCost. Default Value 30
Returns
True if successful, false otherwise

Definition at line 1475 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setEnableCUDA ( const bool  enable = true) const

Enables CUDA support.

Note
Needs Ensenso SDK version >= 2.1.7
Parameters
[in]enableWhen set to true some commands will use CUDA to improve Perfomance
Returns
True if successful, false otherwise

Definition at line 1029 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setExposure ( const float  exposure = 1.0) const

The current image exposure time.

Parameters
[in]exposureSpecifies the camera's exposure time in milliseconds.
Returns
True if successful, false otherwise
Note
Have a look at the exposure limits of the LED flash by looking at the illumination topic for your camera model and the MaxFlashTime node.

Definition at line 1142 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFarPlane ( const int  far)

Specifies the maximum distance to the ViewPose below which surface elements will be excluded from the depth map.

Note
This can be used to exclude the working plane from the depth view.
Parameters
[in]farThe clipping plane distance from the camera pose in viewing direction.
Returns
True if successful, false otherwise

Definition at line 1625 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFillBorderSpread ( const int  maximumspread) const

Defines which missing regions will be filled by setting a threshold on the maximum spread of the disparities on the region boundary. Setting this value reasonably small will ensure that only missing patches inside planar faces will be filled whereas gaps at depth discontinuities are kept unfilled.

Parameters
[in]maximumspreadAn integer specifying the maximum spread of the disparities at the fill region border.
Returns
True if successful, false otherwise

Definition at line 1571 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFillRegionSize ( const int  regionsize) const

Defines an upper limit on the region size in pixels, up to which a region is accepted for filling. The region must also satisfy the BorderSpread condition to be filled.

Parameters
[in]regionsizeAn integer specifying region size in pixels, up to which a missing region is being filled.
Note
Setting this parameter to 0 disables the hole filling filter.
Returns
True if successful, false otherwise

Definition at line 1587 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFindPattern ( const bool  enable = true)

Controls, whether the grabber will try finding the pattern in the scene.

Parameters
[in]enableWhen set to true the grabber will try finding the pattern in the scene.
Returns
True if successful, false otherwise

Definition at line 1054 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFlexView ( const bool  enable = false,
const int  imagepairs = 2 
) const

The number of image pairs to capture. When FlexView is set to false the camera will operate in normal one-shot stereo mode. If FlexView is enabled the Capture command will automatically capture the indicated number of image pairs and shift the projectors pattern between each exposure. All image pairs will then be used to compute depth data in ComputeDisparityMap. Using more than one image pair will increase the effective X, Y and Z resolution.

Parameters
[in]enableSpecify false to disable the FlexView function.
[in]imagepairsA value in the range 2..8 specifying the number of image pairs used for depth computation.
Returns
True if successful, false otherwise
Note
This parameter is only present if your camera supports FlexView (all N35 camera models).
FlexView is currently only supported in software triggered operation.
Depth computation from more than one image pair will only yield accurate depth data on scene parts which remained static in all image pairs.

Definition at line 1158 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setFrontLight ( const bool  enable = false) const

Enables the diffuse front light during exposure. This should only be used when calibrating or tracking a calibration pattern. Please also note the illumination limitations.

Parameters
[in]enableWhen set to true the camera's front LED will be switched on for the duration of the image exposure.
Returns
True if successful, false otherwise

Definition at line 1178 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setGain ( const float  gain = 1.0) const

The current analog gain factor. See also MaxGain.

Parameters
[in]gainA value in the range 1..MaxGain specifying the camera's analog gain factor. E.g. setting a value of 2.0 will double the brightness values.
Returns
True if successful, false otherwise

Definition at line 1194 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setGainBoost ( const bool  enable = false) const

Enables the cameras analog gain boost function.

Parameters
[in]enableWhen set to true an additional analog gain boost on the camera will be enabled.
Returns
True if successful, false otherwise

Definition at line 1210 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setGridSpacing ( const double  grid_spacing) const

Sets the grid spacing of the calibration pattern.

Parameters
[in]grid_spacingdistance of two neighboring grid points along the pattern's x or y axis.
Returns
True if successful, false otherwise

Definition at line 1226 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setHardwareGamma ( const bool  enable = true) const

Enables the camera's internal analog gamma correction. This boosts dark pixels while compressing higher brightness values.

Parameters
[in]enableWhen set to true the cameras analog gamma correction will be enabled.
Returns
True if successful, false otherwise

Definition at line 1240 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setHdr ( const bool  enable = false) const

Enables the camera's high dynamic range function with a fixed, piece-wise linear response curve.

Parameters
[in]enableWhen set to true the HDR function of the camera will be enabled.
Returns
True if successful, false otherwise
Note
The response curve set by the HDR feature can currently not be modified.

Definition at line 1256 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setMedianFilterRadius ( const int  radius) const

Specifies the size of the median filter as radius in pixels, excluding the center pixel. The filter is applied to the disparity map. Median filtering will reduce noise inside surfaces while maintaining sharp edges, but object corners will be rounded.

Parameters
[in]radiusAn integer specifying half the median filter window size in pixels, excluding the center pixel. Allowed values are 0 to 2.
Note
Setting the filter radius to 0 will disable median filtering.
Returns
True if successful, false otherwise

Definition at line 1523 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setMinimumDisparity ( const int  disparity = -64) const

The minimum disparity in pixels where correspondences in the stereo image pair are being searched. The resolution reductions by Scaling and Binning are automatically accounted for. The actual value used in the matching process is output in ScaledMinimumDisparity.

Parameters
[in]disparityAn integer specifying the minimum disparity in pixels where the stereo matching algorithm searches for correspondences between the two images.
Returns
True if successful, false otherwise

Definition at line 1272 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setNearPlane ( const int  near)

Specifies the minimum distance to the ViewPose below which surface elements will be excluded from the depth map.

Note
This can be used to exclude the working plane from the depth view.
Parameters
[in]nearThe clipping plane distance from the camera pose in viewing direction.
Returns
True if successful, false otherwise

Definition at line 1619 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setNumberOfDisparities ( const int  number = 128) const

The number of disparities in pixels where correspondences in the stereo image pair are being searched, starting at MinDisparity. The resolution reductions by Scaling and Binning are automatically accounted for. The actual value used in the matching process is output in ScaledNumberOfDisparities.

Parameters
[in]numberAn integer specifying the number of disparities in pixels where the images are being matched.
Returns
True if successful, false otherwise
Note
Note: The NumberOfDisparities parameter must be a multiple of 16.

Definition at line 1288 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setOptimizationProfile ( const std::string  profile = "AlignedAndDiagonal") const

The type of Semi-Global-Matching optimization carried out on the cost function.

Parameters
[in]profileThree possible types are accepted:
  • "Aligned": Propagate cost along 4 paths, corresonding to the pixel axes of the rectified images.
  • "Diagonal": Propagate cost on the 4 paths, corresponding the all 45 degree pixel diagonals.
  • "AlignedAndDiagonal": Propagate along all 8 paths, aligned and diagonal. This setting yields the best matching results, but slowest performance.
Returns
True if successful, false otherwise
Note
The Aligned and Diagonal profiles have similar runtime, but object edges that are approximately aligned with one of the propagation directions might be estimated less accurately. You might for example choose the Diagonal profile, if you expect you object edges to be mostly pixel axis aligned and Aligned for best results on non-pixel aligned object boundaries.

Definition at line 1304 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setPixelClock ( const int  pixel_clock = 24) const

Sets the pixel clock in MHz. If you have too many devices on the same bus the image transfer might fail when the clock is too high. This happens when the host PC does not request data from the camera fast enough. The sensor then outputs data faster than it can be transferred to the host and the cameras buffer will overflow. Thus the image transfer is incomplete and the image is lost.

Parameters
[in]pixel_clockAn integer number specifying the cameras pixel clock in MHz. Range: [7-43]
Returns
True if successful, false otherwise

Definition at line 1320 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setProjector ( const bool  enable = true) const

Enables the texture projector during exposure. This should only be used for depth map computation. Please also note the illumination limitations.

Parameters
[in]enableWhen set to true the camera's pattern projector will be switched on for the duration of the image exposure.
Returns
True if successful, false otherwise

Definition at line 1336 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setRGBTriggerDelay ( const float  delay = 10) const

The delay between trigger of the stereo camera (and projector) and the RGB camera.

Note
This can be used to avoid the projector pattern being visible in RGB.
Parameters
[in]delayTrigger delay in ms.
Returns
True if successful, false otherwise

Definition at line 1400 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setScaling ( const float  scaling = 1.0) const

Scaling allows to reduce the camera resolution by an arbitrary non-integer factor during rectification. The camera raw images stay at their original size, but the rectified images, DisparityMap and PointMap will be scaled by the specified factor to improve stereo matching runtime. This allows you to choose you own tradeoff between image resolution and performance.

Parameters
[in]scalingAn positive real number between 0.25 and 1.0.
Returns
True if successful, false otherwise
Note
Setting a new Scaling factor immediately clears and resizes the affected image nodes.
As Scaling only affects the rectified images you might set a new Scaling factor and rerun ComputeDisparityMap without capturing a new image pair! You could therefore use Scaling for fast object detection in low resolution, and then perform measurements in higher resolution by setting Scaling to 1 without the need to capture an additional image pair.

Definition at line 1368 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setShadowingThreshold ( const int  shadowingthreshold) const

The disparity map is checked for occluded pixels. This is usually called 'left-right consistency check'. A pixel is only accepted if it is a mutually best match with the assigned right image pixel. Due to subpixel interpolation and half-occluded pixels, it is reasonable to allow small deviations from 'exact mutual' matches. This threshold sets the allowed range of mismatch in pixels.

Parameters
[in]shadowingthresholdAn integer specifying the threshold in disparities by which a pixel might be occluded by another pixel to still be accepted as valid. Negative values disable the occlusion detection and will leave wrongly associated regions in occluded image areas.
Returns
True if successful, false otherwise
Note
Setting a negative value (e.g. -1) for this parameter will disable filtering of shadowed areas. This will leave arbitrary depth values in shadowed areas. Default Value 1

Definition at line 1491 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setSpeckleComponentThreshold ( const int  threshold) const

Defines how the image is divided into regions for speckle filtering. Whenever two neighboring pixel disparities differ by more than ComponentThreshold disparities, the two pixels are considered as belonging to separate regions. Consequently, each resulting region will not have discontinuities larger or equal to ComponentThreshold in it's disparity map area.

Parameters
[in]thresholdAn integer specifying the disparity step size, where surfaces should be cut into separate speckle regions.
Note
The smaller this threshold is set, the smaller the resulting disparity regions will be. Thus setting a smaller ComponentThreshold will result in more regions being filtered out, because some regions fall apart and their sizes drop below RegionSize.
Returns
True if successful, false otherwise

Definition at line 1539 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setSpeckleRegionSize ( const int  threshold) const

The size in pixels of a disparity map region below which the region will be removed from the disparity map. The computation of the regions is controlled by ComponentThreshold.

Parameters
[in]thresholdAn integer specifying the size in pixels below which a region will be removed from the disparity map.
Note
Setting this parameter to 0 disables the speckle filter.
Returns
True if successful, false otherwise

Definition at line 1555 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setSurfaceConnectivity ( const int  threshold) const

The distance along a camera's z direction below which two neighboring points will be connected to a surface triangle.

Parameters
[in]thresholdA threshold in millimeters below which neighboring pixels will be connected to a small surface patch.
Returns
True if successful, false otherwise

Definition at line 1603 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setTargetBrightness ( const int  target = 80) const

The desired average image brightness in gray values used for AutoExposure and AutoGain.

Parameters
[in]targetPositive number from 40 to 210, specifying the desired average gray value of both images.
Returns
True if successful, false otherwise

Definition at line 1352 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setTriggerMode ( const std::string  mode = "Software") const

Specifies how an image capture is initiated.

Parameters
[in]modeThree possible mode are accepted:
  • "Software": The camera starts the exposure by software trigger when the Capture command is issued.
  • "FallingEdge": The Capture command waits for a high-to-low transition on the trigger input before starting the exposure.
  • "RisingEdge": The Capture command waits for a low-to-high transition on the trigger input before starting the exposure.
Returns
True if successful, false otherwise
Note
Triggering on the rising edge is currently not supported by the N10 cameras due to hardware limitations.

Definition at line 1384 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setUniquenessRatio ( const int  ratio) const

Filters the pixels depending on the uniqueness of the found correspondence. The value indicates the percentage, by which the cost of the next best correspondence must be larger (compared to the best correspondence), such that the pixel is accepted.

Parameters
[in]ratioAn integer specifying the uniqueness margin in percent.
Note
Setting this parameter to 0 disables the uniqueness filter.
Returns
True if successful, false otherwise

Definition at line 1507 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setUseDisparityMapAreaOfInterest ( const bool  enable = false) const

Reduces the camera's capture AOI to the region necessary for the currently set stereo matching AOI. This will reduce the image transfer time, especially when setting smaller AOIs for the stereo matching.

Parameters
[in]enableWhen set to true the camera's capture AOI will be reduced.
Returns
True if successful, false otherwise
Note
On N20, N30 and N35 cameras the AOI will only reduce the number of lines transferred in the raw images. Each line will still contain valid pixels for the full sensor width.
This will also slightly improve transfer times when the stereo matching AOI is set to full size, because it crops image portions that will be thrown away during image rectification.
Beware that you cannot enlarge the stereo matching AOI when you captured an image with UseDisparityMapAreaOfInterest set to true, because the camera images contain no data outside the previously specified AOI. You need to capture another image after enlarging the stereo matching AOI in order to get valid depth data in the enlarged regions.

Definition at line 1420 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setUseOpenGL ( const bool  enable) const

Configures the use of OpenGL.

Note
OpenGL is used for example in the RenderPointMap command for RGB registration
Parameters
[in]enableto use OpenGL
Returns
True if successful, false otherwise

Definition at line 1436 of file ensenso_grabber.cpp.

bool pcl::EnsensoGrabber::setUseRGB ( const bool  enable = true)

Controls, whether the grabber will use an external ensenso rgb camera.

Parameters
[in]enableWhen set to true the grabber will use an external ensenso rgb camera.
Returns
True if successful, false otherwise

Definition at line 1453 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::start ( )

Start the point cloud and or image acquisition.

Note
Opens device "0" if no device is open

Definition at line 1631 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::stop ( )

Stop the data acquisition.

Definition at line 1644 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::storeCalibrationPattern ( const bool  enable)

Enables collecting the calibration pattern continuous during processGrabbing()

Parameters
[in]enableWhen set to true the calibration pattern raw and pose will be collected.

Definition at line 993 of file ensenso_grabber.cpp.

void pcl::EnsensoGrabber::triggerCameras ( )
protected

triggers all available cameras

Definition at line 958 of file ensenso_grabber.cpp.

Member Data Documentation

NxLibItem pcl::EnsensoGrabber::camera_
protected

References to the camera tree.

Definition at line 549 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::device_open_
protected

Whether an Ensenso device is opened or not.

Definition at line 564 of file ensenso_grabber.h.

int pcl::EnsensoGrabber::far_plane_
protected

Far plane Parameter for the RenderPointMap command.

Definition at line 591 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::find_pattern_
protected

Whether the grabber tries to find the pattern or not.

Definition at line 560 of file ensenso_grabber.h.

float pcl::EnsensoGrabber::fps_
protected

Camera frames per second (FPS)

Definition at line 594 of file ensenso_grabber.h.

boost::mutex pcl::EnsensoGrabber::fps_mutex_
mutableprotected

Mutual exclusion for FPS computation.

Definition at line 603 of file ensenso_grabber.h.

boost::thread pcl::EnsensoGrabber::grabber_thread_
protected

Grabber thread.

Definition at line 531 of file ensenso_grabber.h.

boost::signals2::signal<sig_cb_ensenso_image_depth>* pcl::EnsensoGrabber::image_depth_signal_
protected

Boost depth image signal.

Definition at line 546 of file ensenso_grabber.h.

boost::signals2::signal<sig_cb_ensenso_images_rgb>* pcl::EnsensoGrabber::images_rgb_signal_
protected

Boost images rgb signal.

Definition at line 543 of file ensenso_grabber.h.

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

Boost images signal.

Definition at line 540 of file ensenso_grabber.h.

Eigen::Affine3d pcl::EnsensoGrabber::last_pattern_pose_
protected

Last pose of the detected pattern during processGrabbing()

Definition at line 573 of file ensenso_grabber.h.

std::string pcl::EnsensoGrabber::last_stereo_pattern_
protected

Last raw stereo info of the detected pattern during processGrabbing()

Definition at line 576 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::mono_device_open_
protected

Whether an Ensenso device is opened or not.

Definition at line 567 of file ensenso_grabber.h.

NxLibItem pcl::EnsensoGrabber::monocam_
protected

Definition at line 551 of file ensenso_grabber.h.

int pcl::EnsensoGrabber::near_plane_
protected

Near plane Parameter for the RenderPointMap command.

Definition at line 588 of file ensenso_grabber.h.

boost::mutex pcl::EnsensoGrabber::pattern_mutex_
mutableprotected

Mutual exclusion for reading pattern pose.

Definition at line 582 of file ensenso_grabber.h.

boost::signals2::signal<sig_cb_ensenso_point_cloud_rgb>* pcl::EnsensoGrabber::point_cloud_rgb_signal_
protected

Boost point cloud signal with RGB.

Definition at line 537 of file ensenso_grabber.h.

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

Boost point cloud signal.

Definition at line 534 of file ensenso_grabber.h.

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

Reference to the NxLib tree root.

Definition at line 554 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::running_
protected

Whether an Ensenso device is running or not.

Definition at line 585 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::store_calibration_pattern_
protected

Whether to read the pattern pose at processGrabbing() or not.

Definition at line 579 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::tcp_open_
protected

Whether an TCP port is opened or not.

Definition at line 570 of file ensenso_grabber.h.

Transform pcl::EnsensoGrabber::tf_left_to_rgb_
protected

translation from left camera to RGB frame

Definition at line 600 of file ensenso_grabber.h.

double pcl::EnsensoGrabber::timestamp_
protected

timestamp of the current frame

Definition at line 597 of file ensenso_grabber.h.

bool pcl::EnsensoGrabber::use_rgb_
protected

Whether the grabber uses RGB or not.

Definition at line 557 of file ensenso_grabber.h.


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


ensenso
Author(s): Francisco Suarez Ruiz
autogenerated on Sat Feb 16 2019 03:42:20