Point Cloud Library (PCL)  1.14.1-dev
List of all members | Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::OpenNIGrabber Class Reference

Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live) More...

#include <pcl/io/openni_grabber.h>

+ Inheritance diagram for pcl::OpenNIGrabber:
+ Collaboration diagram for pcl::OpenNIGrabber:

Classes

struct  modeComp
 

Public Types

enum  Mode {
  OpenNI_Default_Mode = 0 , OpenNI_SXGA_15Hz = 1 , OpenNI_VGA_30Hz = 2 , OpenNI_VGA_25Hz = 3 ,
  OpenNI_QVGA_25Hz = 4 , OpenNI_QVGA_30Hz = 5 , OpenNI_QVGA_60Hz = 6 , OpenNI_QQVGA_25Hz = 7 ,
  OpenNI_QQVGA_30Hz = 8 , OpenNI_QQVGA_60Hz = 9
}
 
using Ptr = shared_ptr< OpenNIGrabber >
 
using ConstPtr = shared_ptr< const OpenNIGrabber >
 
using sig_cb_openni_image = void(const openni_wrapper::Image::Ptr &)
 
using sig_cb_openni_depth_image = void(const openni_wrapper::DepthImage::Ptr &)
 
using sig_cb_openni_ir_image = void(const openni_wrapper::IRImage::Ptr &)
 
using sig_cb_openni_image_depth_image = void(const openni_wrapper::Image::Ptr &, const openni_wrapper::DepthImage::Ptr &, float)
 
using sig_cb_openni_ir_depth_image = void(const openni_wrapper::IRImage::Ptr &, const openni_wrapper::DepthImage::Ptr &, float)
 
using sig_cb_openni_point_cloud = void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &)
 
using sig_cb_openni_point_cloud_rgb = void(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &)
 
using sig_cb_openni_point_cloud_rgba = void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &)
 
using sig_cb_openni_point_cloud_i = void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &)
 

Public Member Functions

 OpenNIGrabber (const std::string &device_id="", const Mode &depth_mode=OpenNI_Default_Mode, const Mode &image_mode=OpenNI_Default_Mode)
 Constructor. More...
 
 ~OpenNIGrabber () noexcept override
 virtual Destructor inherited from the Grabber interface. More...
 
void start () override
 Start the data acquisition. More...
 
void stop () override
 Stop the data acquisition. More...
 
bool isRunning () const override
 Check if the data acquisition is still running. More...
 
std::string getName () const override
 returns the name of the concrete subclass. More...
 
float getFramesPerSecond () const override
 Obtain the number of frames per second (FPS). More...
 
openni_wrapper::OpenNIDevice::Ptr getDevice () const
 Get a pcl::shared pointer to the openni_wrapper::OpenNIDevice object. More...
 
std::vector< std::pair< int, XnMapOutputMode > > getAvailableDepthModes () const
 Obtain a list of the available depth modes that this device supports. More...
 
std::vector< std::pair< int, XnMapOutputMode > > getAvailableImageModes () const
 Obtain a list of the available image modes that this device supports. More...
 
void setRGBCameraIntrinsics (const double rgb_focal_length_x, const double rgb_focal_length_y, const double rgb_principal_point_x, const double rgb_principal_point_y)
 Set the RGB camera parameters (fx, fy, cx, cy) More...
 
void getRGBCameraIntrinsics (double &rgb_focal_length_x, double &rgb_focal_length_y, double &rgb_principal_point_x, double &rgb_principal_point_y) const
 Get the RGB camera parameters (fx, fy, cx, cy) More...
 
void setRGBFocalLength (const double rgb_focal_length)
 Set the RGB image focal length (fx = fy). More...
 
void setRGBFocalLength (const double rgb_focal_length_x, const double rgb_focal_length_y)
 Set the RGB image focal length. More...
 
void getRGBFocalLength (double &rgb_focal_length_x, double &rgb_focal_length_y) const
 Return the RGB focal length parameters (fx, fy) More...
 
void setDepthCameraIntrinsics (const double depth_focal_length_x, const double depth_focal_length_y, const double depth_principal_point_x, const double depth_principal_point_y)
 Set the Depth camera parameters (fx, fy, cx, cy) More...
 
void getDepthCameraIntrinsics (double &depth_focal_length_x, double &depth_focal_length_y, double &depth_principal_point_x, double &depth_principal_point_y) const
 Get the Depth camera parameters (fx, fy, cx, cy) More...
 
void setDepthFocalLength (const double depth_focal_length)
 Set the Depth image focal length (fx = fy). More...
 
void setDepthFocalLength (const double depth_focal_length_x, const double depth_focal_length_y)
 Set the Depth image focal length. More...
 
void getDepthFocalLength (double &depth_focal_length_x, double &depth_focal_length_y) const
 Return the Depth focal length parameters (fx, fy) More...
 
void convertShiftToDepth (const std::uint16_t *shift_data_ptr, std::uint16_t *depth_data_ptr, std::size_t size) const
 Convert vector of raw shift values to depth values. 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...
 
Grabberoperator= (const Grabber &)=delete
 No copy assign operator since Grabber can't be copied. More...
 
 Grabber (Grabber &&)=default
 Move ctor. More...
 
Grabberoperator= (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...
 

Protected Member Functions

void onInit (const std::string &device_id, const Mode &depth_mode, const Mode &image_mode)
 On initialization processing. More...
 
void setupDevice (const std::string &device_id, const Mode &depth_mode, const Mode &image_mode)
 Sets up an OpenNI device. More...
 
void updateModeMaps ()
 Update mode maps. More...
 
void startSynchronization ()
 Start synchronization. More...
 
void stopSynchronization ()
 Stop synchronization. More...
 
bool mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const
 Map config modes. More...
 
virtual void imageCallback (openni_wrapper::Image::Ptr image, void *cookie)
 RGB image callback. More...
 
virtual void depthCallback (openni_wrapper::DepthImage::Ptr depth_image, void *cookie)
 Depth image callback. More...
 
virtual void irCallback (openni_wrapper::IRImage::Ptr ir_image, void *cookie)
 IR image callback. More...
 
virtual void imageDepthImageCallback (const openni_wrapper::Image::Ptr &image, const openni_wrapper::DepthImage::Ptr &depth_image)
 RGB + Depth image callback. More...
 
virtual void irDepthImageCallback (const openni_wrapper::IRImage::Ptr &image, const openni_wrapper::DepthImage::Ptr &depth_image)
 IR + Depth image callback. More...
 
void signalsChanged () override
 Process changed signals. More...
 
virtual void checkImageAndDepthSynchronizationRequired ()
 Check if the RGB and Depth images are required to be synchronized or not. More...
 
virtual void checkImageStreamRequired ()
 Check if the RGB image stream is required or not. More...
 
virtual void checkDepthStreamRequired ()
 Check if the depth stream is required or not. More...
 
virtual void checkIRStreamRequired ()
 Check if the IR image stream is required or not. More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr convertToXYZPointCloud (const openni_wrapper::DepthImage::Ptr &depth) const
 Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ> More...
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr convertToXYZRGBPointCloud (const openni_wrapper::Image::Ptr &image, const openni_wrapper::DepthImage::Ptr &depth_image) const
 Convert a Depth + RGB image pair to a pcl::PointCloud<PointT> More...
 
pcl::PointCloud< pcl::PointXYZI >::Ptr convertToXYZIPointCloud (const openni_wrapper::IRImage::Ptr &image, const openni_wrapper::DepthImage::Ptr &depth_image) const
 Convert a Depth + Intensity image pair to a pcl::PointCloud<pcl::PointXYZI> More...
 
- Protected Member Functions inherited from pcl::Grabber
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 ()
 

Protected Attributes

Synchronizer< openni_wrapper::Image::Ptr, openni_wrapper::DepthImage::Ptrrgb_sync_
 
Synchronizer< openni_wrapper::IRImage::Ptr, openni_wrapper::DepthImage::Ptrir_sync_
 
openni_wrapper::OpenNIDevice::Ptr device_
 The actual openni device. More...
 
std::string rgb_frame_id_
 
std::string depth_frame_id_
 
unsigned image_width_ {0}
 
unsigned image_height_ {0}
 
unsigned depth_width_ {0}
 
unsigned depth_height_ {0}
 
bool image_required_ {false}
 
bool depth_required_ {false}
 
bool ir_required_ {false}
 
bool sync_required_ {false}
 
boost::signals2::signal< sig_cb_openni_image > * image_signal_ {}
 
boost::signals2::signal< sig_cb_openni_depth_image > * depth_image_signal_ {}
 
boost::signals2::signal< sig_cb_openni_ir_image > * ir_image_signal_ {}
 
boost::signals2::signal< sig_cb_openni_image_depth_image > * image_depth_image_signal_ {}
 
boost::signals2::signal< sig_cb_openni_ir_depth_image > * ir_depth_image_signal_ {}
 
boost::signals2::signal< sig_cb_openni_point_cloud > * point_cloud_signal_ {}
 
boost::signals2::signal< sig_cb_openni_point_cloud_i > * point_cloud_i_signal_ {}
 
boost::signals2::signal< sig_cb_openni_point_cloud_rgb > * point_cloud_rgb_signal_ {}
 
boost::signals2::signal< sig_cb_openni_point_cloud_rgba > * point_cloud_rgba_signal_ {}
 
std::map< int, XnMapOutputMode > config2xn_map_
 
openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle {}
 
openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle {}
 
openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle {}
 
bool running_ {false}
 
unsigned rgb_array_size_ {0}
 
unsigned depth_buffer_size_ {0}
 
boost::shared_array< unsigned char > rgb_array_
 
boost::shared_array< unsigned short > depth_buffer_
 
boost::shared_array< unsigned short > ir_buffer_
 
double rgb_focal_length_x_
 The RGB image focal length (fx). More...
 
double rgb_focal_length_y_
 The RGB image focal length (fy). More...
 
double rgb_principal_point_x_
 The RGB image principal point (cx). More...
 
double rgb_principal_point_y_
 The RGB image principal point (cy). More...
 
double depth_focal_length_x_
 The depth image focal length (fx). More...
 
double depth_focal_length_y_
 The depth image focal length (fy). More...
 
double depth_principal_point_x_
 The depth image principal point (cx). More...
 
double depth_principal_point_y_
 The depth image principal point (cy). 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 OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live)

Author
Nico Blodow blodo.nosp@m.w@cs.nosp@m..tum..nosp@m.edu, Suat Gedikli gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m

Definition at line 69 of file openni_grabber.h.

Member Typedef Documentation

◆ ConstPtr

using pcl::OpenNIGrabber::ConstPtr = shared_ptr<const OpenNIGrabber>

Definition at line 73 of file openni_grabber.h.

◆ Ptr

Definition at line 72 of file openni_grabber.h.

◆ sig_cb_openni_depth_image

Definition at line 91 of file openni_grabber.h.

◆ sig_cb_openni_image

Definition at line 90 of file openni_grabber.h.

◆ sig_cb_openni_image_depth_image

Definition at line 93 of file openni_grabber.h.

◆ sig_cb_openni_ir_depth_image

Definition at line 94 of file openni_grabber.h.

◆ sig_cb_openni_ir_image

Definition at line 92 of file openni_grabber.h.

◆ sig_cb_openni_point_cloud

Definition at line 95 of file openni_grabber.h.

◆ sig_cb_openni_point_cloud_i

Definition at line 98 of file openni_grabber.h.

◆ sig_cb_openni_point_cloud_rgb

Definition at line 96 of file openni_grabber.h.

◆ sig_cb_openni_point_cloud_rgba

Definition at line 97 of file openni_grabber.h.

Member Enumeration Documentation

◆ Mode

Enumerator
OpenNI_Default_Mode 
OpenNI_SXGA_15Hz 
OpenNI_VGA_30Hz 
OpenNI_VGA_25Hz 
OpenNI_QVGA_25Hz 
OpenNI_QVGA_30Hz 
OpenNI_QVGA_60Hz 
OpenNI_QQVGA_25Hz 
OpenNI_QQVGA_30Hz 
OpenNI_QQVGA_60Hz 

Definition at line 75 of file openni_grabber.h.

Constructor & Destructor Documentation

◆ OpenNIGrabber()

pcl::OpenNIGrabber::OpenNIGrabber ( const std::string &  device_id = "",
const Mode depth_mode = OpenNI_Default_Mode,
const Mode image_mode = OpenNI_Default_Mode 
)

Constructor.

Parameters
[in]device_idID of the device, which might be a serial number, bus@address or the index of the device.
[in]depth_modethe mode of the depth stream
[in]image_modethe mode of the image stream

◆ ~OpenNIGrabber()

pcl::OpenNIGrabber::~OpenNIGrabber ( )
overridenoexcept

virtual Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

◆ checkDepthStreamRequired()

virtual void pcl::OpenNIGrabber::checkDepthStreamRequired ( )
protectedvirtual

Check if the depth stream is required or not.

◆ checkImageAndDepthSynchronizationRequired()

virtual void pcl::OpenNIGrabber::checkImageAndDepthSynchronizationRequired ( )
protectedvirtual

Check if the RGB and Depth images are required to be synchronized or not.

◆ checkImageStreamRequired()

virtual void pcl::OpenNIGrabber::checkImageStreamRequired ( )
protectedvirtual

Check if the RGB image stream is required or not.

◆ checkIRStreamRequired()

virtual void pcl::OpenNIGrabber::checkIRStreamRequired ( )
protectedvirtual

Check if the IR image stream is required or not.

◆ convertShiftToDepth()

void pcl::OpenNIGrabber::convertShiftToDepth ( const std::uint16_t *  shift_data_ptr,
std::uint16_t *  depth_data_ptr,
std::size_t  size 
) const
inline

Convert vector of raw shift values to depth values.

Parameters
[in]shift_data_ptrinput shift data
[out]depth_data_ptrgenerated depth data
[in]sizeof shift and depth buffer

Definition at line 300 of file openni_grabber.h.

◆ convertToXYZIPointCloud()

pcl::PointCloud<pcl::PointXYZI>::Ptr pcl::OpenNIGrabber::convertToXYZIPointCloud ( const openni_wrapper::IRImage::Ptr image,
const openni_wrapper::DepthImage::Ptr depth_image 
) const
protected

Convert a Depth + Intensity image pair to a pcl::PointCloud<pcl::PointXYZI>

Parameters
[in]imagethe IR image to convert
[in]depth_imagethe depth image to convert

◆ convertToXYZPointCloud()

pcl::PointCloud<pcl::PointXYZ>::Ptr pcl::OpenNIGrabber::convertToXYZPointCloud ( const openni_wrapper::DepthImage::Ptr depth) const
protected

Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>

Parameters
[in]depththe depth image to convert

◆ convertToXYZRGBPointCloud()

template<typename PointT >
pcl::PointCloud<PointT>::Ptr pcl::OpenNIGrabber::convertToXYZRGBPointCloud ( const openni_wrapper::Image::Ptr image,
const openni_wrapper::DepthImage::Ptr depth_image 
) const
protected

Convert a Depth + RGB image pair to a pcl::PointCloud<PointT>

Parameters
[in]imagethe RGB image to convert
[in]depth_imagethe depth image to convert

◆ depthCallback()

virtual void pcl::OpenNIGrabber::depthCallback ( openni_wrapper::DepthImage::Ptr  depth_image,
void *  cookie 
)
protectedvirtual

Depth image callback.

◆ getAvailableDepthModes()

std::vector<std::pair<int, XnMapOutputMode> > pcl::OpenNIGrabber::getAvailableDepthModes ( ) const

Obtain a list of the available depth modes that this device supports.

◆ getAvailableImageModes()

std::vector<std::pair<int, XnMapOutputMode> > pcl::OpenNIGrabber::getAvailableImageModes ( ) const

Obtain a list of the available image modes that this device supports.

◆ getDepthCameraIntrinsics()

void pcl::OpenNIGrabber::getDepthCameraIntrinsics ( double &  depth_focal_length_x,
double &  depth_focal_length_y,
double &  depth_principal_point_x,
double &  depth_principal_point_y 
) const
inline

Get the Depth camera parameters (fx, fy, cx, cy)

Parameters
[out]depth_focal_length_xthe Depth focal length (fx)
[out]depth_focal_length_ythe Depth focal length (fy)
[out]depth_principal_point_xthe Depth principal point (cx)
[out]depth_principal_point_ythe Depth principal point (cy)

Definition at line 247 of file openni_grabber.h.

◆ getDepthFocalLength()

void pcl::OpenNIGrabber::getDepthFocalLength ( double &  depth_focal_length_x,
double &  depth_focal_length_y 
) const
inline

Return the Depth focal length parameters (fx, fy)

Parameters
[out]depth_focal_length_xthe Depth focal length (fx)
[out]depth_focal_length_ythe Depth focal length (fy)

Definition at line 288 of file openni_grabber.h.

◆ getDevice()

openni_wrapper::OpenNIDevice::Ptr pcl::OpenNIGrabber::getDevice ( ) const
inline

Get a pcl::shared pointer to the openni_wrapper::OpenNIDevice object.

Definition at line 496 of file openni_grabber.h.

References device_.

◆ getFramesPerSecond()

float pcl::OpenNIGrabber::getFramesPerSecond ( ) const
overridevirtual

Obtain the number of frames per second (FPS).

Implements pcl::Grabber.

◆ getName()

std::string pcl::OpenNIGrabber::getName ( ) const
overridevirtual

returns the name of the concrete subclass.

Returns
the name of the concrete driver.

Implements pcl::Grabber.

◆ getRGBCameraIntrinsics()

void pcl::OpenNIGrabber::getRGBCameraIntrinsics ( double &  rgb_focal_length_x,
double &  rgb_focal_length_y,
double &  rgb_principal_point_x,
double &  rgb_principal_point_y 
) const
inline

Get the RGB camera parameters (fx, fy, cx, cy)

Parameters
[out]rgb_focal_length_xthe RGB focal length (fx)
[out]rgb_focal_length_ythe RGB focal length (fy)
[out]rgb_principal_point_xthe RGB principal point (cx)
[out]rgb_principal_point_ythe RGB principal point (cy)

Definition at line 171 of file openni_grabber.h.

◆ getRGBFocalLength()

void pcl::OpenNIGrabber::getRGBFocalLength ( double &  rgb_focal_length_x,
double &  rgb_focal_length_y 
) const
inline

Return the RGB focal length parameters (fx, fy)

Parameters
[out]rgb_focal_length_xthe RGB focal length (fx)
[out]rgb_focal_length_ythe RGB focal length (fy)

Definition at line 214 of file openni_grabber.h.

◆ imageCallback()

virtual void pcl::OpenNIGrabber::imageCallback ( openni_wrapper::Image::Ptr  image,
void *  cookie 
)
protectedvirtual

RGB image callback.

◆ imageDepthImageCallback()

virtual void pcl::OpenNIGrabber::imageDepthImageCallback ( const openni_wrapper::Image::Ptr image,
const openni_wrapper::DepthImage::Ptr depth_image 
)
protectedvirtual

RGB + Depth image callback.

◆ irCallback()

virtual void pcl::OpenNIGrabber::irCallback ( openni_wrapper::IRImage::Ptr  ir_image,
void *  cookie 
)
protectedvirtual

IR image callback.

◆ irDepthImageCallback()

virtual void pcl::OpenNIGrabber::irDepthImageCallback ( const openni_wrapper::IRImage::Ptr image,
const openni_wrapper::DepthImage::Ptr depth_image 
)
protectedvirtual

IR + Depth image callback.

◆ isRunning()

bool pcl::OpenNIGrabber::isRunning ( ) const
overridevirtual

Check if the data acquisition is still running.

Implements pcl::Grabber.

◆ mapConfigMode2XnMode()

bool pcl::OpenNIGrabber::mapConfigMode2XnMode ( int  mode,
XnMapOutputMode &  xnmode 
) const
protected

Map config modes.

◆ onInit()

void pcl::OpenNIGrabber::onInit ( const std::string &  device_id,
const Mode depth_mode,
const Mode image_mode 
)
protected

On initialization processing.

◆ setDepthCameraIntrinsics()

void pcl::OpenNIGrabber::setDepthCameraIntrinsics ( const double  depth_focal_length_x,
const double  depth_focal_length_y,
const double  depth_principal_point_x,
const double  depth_principal_point_y 
)
inline

Set the Depth camera parameters (fx, fy, cx, cy)

Parameters
[in]depth_focal_length_xthe Depth focal length (fx)
[in]depth_focal_length_ythe Depth focal length (fy)
[in]depth_principal_point_xthe Depth principal point (cx)
[in]depth_principal_point_ythe Depth principal point (cy) Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them and the grabber will use the default values from the camera instead.

Definition at line 229 of file openni_grabber.h.

◆ setDepthFocalLength() [1/2]

void pcl::OpenNIGrabber::setDepthFocalLength ( const double  depth_focal_length)
inline

Set the Depth image focal length (fx = fy).

Parameters
[in]depth_focal_lengththe Depth focal length (assumes fx = fy) Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it and the grabber will use the default values from the camera instead.

Definition at line 264 of file openni_grabber.h.

◆ setDepthFocalLength() [2/2]

void pcl::OpenNIGrabber::setDepthFocalLength ( const double  depth_focal_length_x,
const double  depth_focal_length_y 
)
inline

Set the Depth image focal length.

Parameters
[in]depth_focal_length_xthe Depth focal length (fx)
[in]depth_focal_length_ythe Depth focal length (fy) Setting the parameter to non-finite values (e.g., NaN, Inf) invalidates them and the grabber will use the default values from the camera instead.

Definition at line 277 of file openni_grabber.h.

◆ setRGBCameraIntrinsics()

void pcl::OpenNIGrabber::setRGBCameraIntrinsics ( const double  rgb_focal_length_x,
const double  rgb_focal_length_y,
const double  rgb_principal_point_x,
const double  rgb_principal_point_y 
)
inline

Set the RGB camera parameters (fx, fy, cx, cy)

Parameters
[in]rgb_focal_length_xthe RGB focal length (fx)
[in]rgb_focal_length_ythe RGB focal length (fy)
[in]rgb_principal_point_xthe RGB principal point (cx)
[in]rgb_principal_point_ythe RGB principal point (cy) Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them and the grabber will use the default values from the camera instead.

Definition at line 153 of file openni_grabber.h.

◆ setRGBFocalLength() [1/2]

void pcl::OpenNIGrabber::setRGBFocalLength ( const double  rgb_focal_length)
inline

Set the RGB image focal length (fx = fy).

Parameters
[in]rgb_focal_lengththe RGB focal length (assumes fx = fy) Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it and the grabber will use the default values from the camera instead. These parameters will be used for XYZRGBA clouds.

Definition at line 190 of file openni_grabber.h.

◆ setRGBFocalLength() [2/2]

void pcl::OpenNIGrabber::setRGBFocalLength ( const double  rgb_focal_length_x,
const double  rgb_focal_length_y 
)
inline

Set the RGB image focal length.

Parameters
[in]rgb_focal_length_xthe RGB focal length (fx)
[in]rgb_focal_length_ythe RGB focal length (fy) Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them and the grabber will use the default values from the camera instead. These parameters will be used for XYZRGBA clouds.

Definition at line 203 of file openni_grabber.h.

◆ setupDevice()

void pcl::OpenNIGrabber::setupDevice ( const std::string &  device_id,
const Mode depth_mode,
const Mode image_mode 
)
protected

Sets up an OpenNI device.

◆ signalsChanged()

void pcl::OpenNIGrabber::signalsChanged ( )
overrideprotectedvirtual

Process changed signals.

Reimplemented from pcl::Grabber.

◆ start()

void pcl::OpenNIGrabber::start ( )
overridevirtual

Start the data acquisition.

Implements pcl::Grabber.

◆ startSynchronization()

void pcl::OpenNIGrabber::startSynchronization ( )
protected

Start synchronization.

◆ stop()

void pcl::OpenNIGrabber::stop ( )
overridevirtual

Stop the data acquisition.

Implements pcl::Grabber.

◆ stopSynchronization()

void pcl::OpenNIGrabber::stopSynchronization ( )
protected

Stop synchronization.

◆ updateModeMaps()

void pcl::OpenNIGrabber::updateModeMaps ( )
protected

Update mode maps.

Member Data Documentation

◆ config2xn_map_

std::map<int, XnMapOutputMode> pcl::OpenNIGrabber::config2xn_map_
protected

Definition at line 461 of file openni_grabber.h.

◆ depth_buffer_

boost::shared_array<unsigned short> pcl::OpenNIGrabber::depth_buffer_
mutableprotected

Definition at line 471 of file openni_grabber.h.

◆ depth_buffer_size_

unsigned pcl::OpenNIGrabber::depth_buffer_size_ {0}
mutableprotected

Definition at line 469 of file openni_grabber.h.

◆ depth_callback_handle

openni_wrapper::OpenNIDevice::CallbackHandle pcl::OpenNIGrabber::depth_callback_handle {}
protected

Definition at line 463 of file openni_grabber.h.

◆ depth_focal_length_x_

double pcl::OpenNIGrabber::depth_focal_length_x_
protected

The depth image focal length (fx).

Definition at line 483 of file openni_grabber.h.

◆ depth_focal_length_y_

double pcl::OpenNIGrabber::depth_focal_length_y_
protected

The depth image focal length (fy).

Definition at line 485 of file openni_grabber.h.

◆ depth_frame_id_

std::string pcl::OpenNIGrabber::depth_frame_id_
protected

Definition at line 424 of file openni_grabber.h.

◆ depth_height_

unsigned pcl::OpenNIGrabber::depth_height_ {0}
protected

Definition at line 428 of file openni_grabber.h.

◆ depth_image_signal_

boost::signals2::signal<sig_cb_openni_depth_image>* pcl::OpenNIGrabber::depth_image_signal_ {}
protected

Definition at line 436 of file openni_grabber.h.

◆ depth_principal_point_x_

double pcl::OpenNIGrabber::depth_principal_point_x_
protected

The depth image principal point (cx).

Definition at line 487 of file openni_grabber.h.

◆ depth_principal_point_y_

double pcl::OpenNIGrabber::depth_principal_point_y_
protected

The depth image principal point (cy).

Definition at line 489 of file openni_grabber.h.

◆ depth_required_

bool pcl::OpenNIGrabber::depth_required_ {false}
protected

Definition at line 431 of file openni_grabber.h.

◆ depth_width_

unsigned pcl::OpenNIGrabber::depth_width_ {0}
protected

Definition at line 427 of file openni_grabber.h.

◆ device_

openni_wrapper::OpenNIDevice::Ptr pcl::OpenNIGrabber::device_
protected

The actual openni device.

Definition at line 421 of file openni_grabber.h.

Referenced by getDevice().

◆ image_callback_handle

openni_wrapper::OpenNIDevice::CallbackHandle pcl::OpenNIGrabber::image_callback_handle {}
protected

Definition at line 464 of file openni_grabber.h.

◆ image_depth_image_signal_

boost::signals2::signal<sig_cb_openni_image_depth_image>* pcl::OpenNIGrabber::image_depth_image_signal_ {}
protected

Definition at line 438 of file openni_grabber.h.

◆ image_height_

unsigned pcl::OpenNIGrabber::image_height_ {0}
protected

Definition at line 426 of file openni_grabber.h.

◆ image_required_

bool pcl::OpenNIGrabber::image_required_ {false}
protected

Definition at line 430 of file openni_grabber.h.

◆ image_signal_

boost::signals2::signal<sig_cb_openni_image>* pcl::OpenNIGrabber::image_signal_ {}
protected

Definition at line 435 of file openni_grabber.h.

◆ image_width_

unsigned pcl::OpenNIGrabber::image_width_ {0}
protected

Definition at line 425 of file openni_grabber.h.

◆ ir_buffer_

boost::shared_array<unsigned short> pcl::OpenNIGrabber::ir_buffer_
mutableprotected

Definition at line 472 of file openni_grabber.h.

◆ ir_callback_handle

openni_wrapper::OpenNIDevice::CallbackHandle pcl::OpenNIGrabber::ir_callback_handle {}
protected

Definition at line 465 of file openni_grabber.h.

◆ ir_depth_image_signal_

boost::signals2::signal<sig_cb_openni_ir_depth_image>* pcl::OpenNIGrabber::ir_depth_image_signal_ {}
protected

Definition at line 439 of file openni_grabber.h.

◆ ir_image_signal_

boost::signals2::signal<sig_cb_openni_ir_image>* pcl::OpenNIGrabber::ir_image_signal_ {}
protected

Definition at line 437 of file openni_grabber.h.

◆ ir_required_

bool pcl::OpenNIGrabber::ir_required_ {false}
protected

Definition at line 432 of file openni_grabber.h.

◆ ir_sync_

Definition at line 418 of file openni_grabber.h.

◆ point_cloud_i_signal_

boost::signals2::signal<sig_cb_openni_point_cloud_i>* pcl::OpenNIGrabber::point_cloud_i_signal_ {}
protected

Definition at line 441 of file openni_grabber.h.

◆ point_cloud_rgb_signal_

boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* pcl::OpenNIGrabber::point_cloud_rgb_signal_ {}
protected

Definition at line 442 of file openni_grabber.h.

◆ point_cloud_rgba_signal_

boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* pcl::OpenNIGrabber::point_cloud_rgba_signal_ {}
protected

Definition at line 443 of file openni_grabber.h.

◆ point_cloud_signal_

boost::signals2::signal<sig_cb_openni_point_cloud>* pcl::OpenNIGrabber::point_cloud_signal_ {}
protected

Definition at line 440 of file openni_grabber.h.

◆ rgb_array_

boost::shared_array<unsigned char> pcl::OpenNIGrabber::rgb_array_
mutableprotected

Definition at line 470 of file openni_grabber.h.

◆ rgb_array_size_

unsigned pcl::OpenNIGrabber::rgb_array_size_ {0}
mutableprotected

Definition at line 468 of file openni_grabber.h.

◆ rgb_focal_length_x_

double pcl::OpenNIGrabber::rgb_focal_length_x_
protected

The RGB image focal length (fx).

Definition at line 475 of file openni_grabber.h.

◆ rgb_focal_length_y_

double pcl::OpenNIGrabber::rgb_focal_length_y_
protected

The RGB image focal length (fy).

Definition at line 477 of file openni_grabber.h.

◆ rgb_frame_id_

std::string pcl::OpenNIGrabber::rgb_frame_id_
protected

Definition at line 423 of file openni_grabber.h.

◆ rgb_principal_point_x_

double pcl::OpenNIGrabber::rgb_principal_point_x_
protected

The RGB image principal point (cx).

Definition at line 479 of file openni_grabber.h.

◆ rgb_principal_point_y_

double pcl::OpenNIGrabber::rgb_principal_point_y_
protected

The RGB image principal point (cy).

Definition at line 481 of file openni_grabber.h.

◆ rgb_sync_

Synchronizer<openni_wrapper::Image::Ptr, openni_wrapper::DepthImage::Ptr > pcl::OpenNIGrabber::rgb_sync_
protected

Definition at line 417 of file openni_grabber.h.

◆ running_

bool pcl::OpenNIGrabber::running_ {false}
protected

Definition at line 466 of file openni_grabber.h.

◆ sync_required_

bool pcl::OpenNIGrabber::sync_required_ {false}
protected

Definition at line 433 of file openni_grabber.h.


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