Point Cloud Library (PCL)  1.9.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:

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
}
 
typedef boost::shared_ptr< OpenNIGrabberPtr
 
typedef boost::shared_ptr< const OpenNIGrabberConstPtr
 
typedef void( sig_cb_openni_image) (const boost::shared_ptr< openni_wrapper::Image > &)
 
typedef void( sig_cb_openni_depth_image) (const boost::shared_ptr< openni_wrapper::DepthImage > &)
 
typedef void( sig_cb_openni_ir_image) (const boost::shared_ptr< openni_wrapper::IRImage > &)
 
typedef void( sig_cb_openni_image_depth_image) (const boost::shared_ptr< openni_wrapper::Image > &, const boost::shared_ptr< openni_wrapper::DepthImage > &, float constant)
 
typedef void( sig_cb_openni_ir_depth_image) (const boost::shared_ptr< openni_wrapper::IRImage > &, const boost::shared_ptr< openni_wrapper::DepthImage > &, float constant)
 
typedef void( sig_cb_openni_point_cloud) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &)
 
typedef void( sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGB > > &)
 
typedef void( sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &)
 
typedef void( sig_cb_openni_point_cloud_i) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &)
 

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...
 
virtual ~OpenNIGrabber () throw ()
 virtual Destructor inherited from the Grabber interface. More...
 
virtual void start ()
 Start the data acquisition. More...
 
virtual void stop ()
 Stop the data acquisition. More...
 
virtual bool isRunning () const
 Check if the data acquisition is still running. More...
 
virtual std::string getName () const
 returns the name of the concrete subclass. More...
 
virtual float getFramesPerSecond () const
 Obtain the number of frames per second (FPS). More...
 
boost::shared_ptr< openni_wrapper::OpenNIDevicegetDevice () const
 Get a boost shared pointer to the pcl::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 uint16_t *shift_data_ptr, 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 ()
 Constructor. More...
 
virtual ~Grabber () throw ()
 virtual destructor. More...
 
template<typename T >
boost::signals2::connection registerCallback (const boost::function< T > &callback)
 registers a callback function/method to a signal with the corresponding signature More...
 
template<typename T >
bool providesCallback () const
 indicates whether a signal with given parameter-type exists or not 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 (boost::shared_ptr< openni_wrapper::Image > image, void *cookie)
 RGB image callback. More...
 
virtual void depthCallback (boost::shared_ptr< openni_wrapper::DepthImage > depth_image, void *cookie)
 Depth image callback. More...
 
virtual void irCallback (boost::shared_ptr< openni_wrapper::IRImage > ir_image, void *cookie)
 IR image callback. More...
 
virtual void imageDepthImageCallback (const boost::shared_ptr< openni_wrapper::Image > &image, const boost::shared_ptr< openni_wrapper::DepthImage > &depth_image)
 RGB + Depth image callback. More...
 
virtual void irDepthImageCallback (const boost::shared_ptr< openni_wrapper::IRImage > &image, const boost::shared_ptr< openni_wrapper::DepthImage > &depth_image)
 IR + Depth image callback. More...
 
virtual void signalsChanged ()
 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...
 
boost::shared_ptr< pcl::PointCloud< pcl::PointXYZ > > convertToXYZPointCloud (const boost::shared_ptr< openni_wrapper::DepthImage > &depth) const
 Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ> More...
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr convertToXYZRGBPointCloud (const boost::shared_ptr< openni_wrapper::Image > &image, const boost::shared_ptr< openni_wrapper::DepthImage > &depth_image) const
 Convert a Depth + RGB image pair to a pcl::PointCloud<PointT> More...
 
boost::shared_ptr< pcl::PointCloud< pcl::PointXYZI > > convertToXYZIPointCloud (const boost::shared_ptr< openni_wrapper::IRImage > &image, const boost::shared_ptr< openni_wrapper::DepthImage > &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
 
template<typename T >
int num_slots () const
 
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< boost::shared_ptr< openni_wrapper::Image >, boost::shared_ptr< openni_wrapper::DepthImage > > rgb_sync_
 
Synchronizer< boost::shared_ptr< openni_wrapper::IRImage >, boost::shared_ptr< openni_wrapper::DepthImage > > ir_sync_
 
boost::shared_ptr< openni_wrapper::OpenNIDevicedevice_
 The actual openni device. More...
 
std::string rgb_frame_id_
 
std::string depth_frame_id_
 
unsigned image_width_
 
unsigned image_height_
 
unsigned depth_width_
 
unsigned depth_height_
 
bool image_required_
 
bool depth_required_
 
bool ir_required_
 
bool sync_required_
 
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_
 
unsigned rgb_array_size_
 
unsigned depth_buffer_size_
 
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, 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 68 of file openni_grabber.h.

Member Typedef Documentation

typedef boost::shared_ptr<const OpenNIGrabber> pcl::OpenNIGrabber::ConstPtr

Definition at line 72 of file openni_grabber.h.

typedef boost::shared_ptr<OpenNIGrabber> pcl::OpenNIGrabber::Ptr

Definition at line 71 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_depth_image) (const boost::shared_ptr< openni_wrapper::DepthImage > &)

Definition at line 90 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_image) (const boost::shared_ptr< openni_wrapper::Image > &)

Definition at line 89 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_image_depth_image) (const boost::shared_ptr< openni_wrapper::Image > &, const boost::shared_ptr< openni_wrapper::DepthImage > &, float constant)

Definition at line 92 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_ir_depth_image) (const boost::shared_ptr< openni_wrapper::IRImage > &, const boost::shared_ptr< openni_wrapper::DepthImage > &, float constant)

Definition at line 93 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_ir_image) (const boost::shared_ptr< openni_wrapper::IRImage > &)

Definition at line 91 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_point_cloud) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZ > > &)

Definition at line 94 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_point_cloud_i) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZI > > &)

Definition at line 97 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGB > > &)

Definition at line 95 of file openni_grabber.h.

typedef void( pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZRGBA > > &)

Definition at line 96 of file openni_grabber.h.

Member Enumeration Documentation

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 74 of file openni_grabber.h.

Constructor & Destructor Documentation

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
virtual pcl::OpenNIGrabber::~OpenNIGrabber ( )
throw (
)
virtual

virtual Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

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

Check if the depth stream is required or not.

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

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

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

Check if the RGB image stream is required or not.

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

Check if the IR image stream is required or not.

void pcl::OpenNIGrabber::convertShiftToDepth ( const uint16_t *  shift_data_ptr,
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 299 of file openni_grabber.h.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > pcl::OpenNIGrabber::convertToXYZIPointCloud ( const boost::shared_ptr< openni_wrapper::IRImage > &  image,
const boost::shared_ptr< openni_wrapper::DepthImage > &  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
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> > pcl::OpenNIGrabber::convertToXYZPointCloud ( const boost::shared_ptr< openni_wrapper::DepthImage > &  depth) const
protected

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

Parameters
[in]depththe depth image to convert
template<typename PointT >
pcl::PointCloud<PointT>::Ptr pcl::OpenNIGrabber::convertToXYZRGBPointCloud ( const boost::shared_ptr< openni_wrapper::Image > &  image,
const boost::shared_ptr< openni_wrapper::DepthImage > &  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
virtual void pcl::OpenNIGrabber::depthCallback ( boost::shared_ptr< openni_wrapper::DepthImage depth_image,
void *  cookie 
)
protectedvirtual

Depth image callback.

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

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

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

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

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 246 of file openni_grabber.h.

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 287 of file openni_grabber.h.

boost::shared_ptr< openni_wrapper::OpenNIDevice > pcl::OpenNIGrabber::getDevice ( ) const
inline

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

Definition at line 499 of file openni_grabber.h.

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

Obtain the number of frames per second (FPS).

Implements pcl::Grabber.

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

returns the name of the concrete subclass.

Returns
the name of the concrete driver.

Implements pcl::Grabber.

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 170 of file openni_grabber.h.

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 213 of file openni_grabber.h.

virtual void pcl::OpenNIGrabber::imageCallback ( boost::shared_ptr< openni_wrapper::Image image,
void *  cookie 
)
protectedvirtual

RGB image callback.

virtual void pcl::OpenNIGrabber::imageDepthImageCallback ( const boost::shared_ptr< openni_wrapper::Image > &  image,
const boost::shared_ptr< openni_wrapper::DepthImage > &  depth_image 
)
protectedvirtual

RGB + Depth image callback.

virtual void pcl::OpenNIGrabber::irCallback ( boost::shared_ptr< openni_wrapper::IRImage ir_image,
void *  cookie 
)
protectedvirtual

IR image callback.

virtual void pcl::OpenNIGrabber::irDepthImageCallback ( const boost::shared_ptr< openni_wrapper::IRImage > &  image,
const boost::shared_ptr< openni_wrapper::DepthImage > &  depth_image 
)
protectedvirtual

IR + Depth image callback.

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

Check if the data acquisition is still running.

Implements pcl::Grabber.

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

Map config modes.

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

On initialization processing.

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 228 of file openni_grabber.h.

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 263 of file openni_grabber.h.

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 276 of file openni_grabber.h.

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 152 of file openni_grabber.h.

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 189 of file openni_grabber.h.

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 202 of file openni_grabber.h.

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

Sets up an OpenNI device.

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

Process changed signals.

Reimplemented from pcl::Grabber.

virtual void pcl::OpenNIGrabber::start ( )
virtual

Start the data acquisition.

Implements pcl::Grabber.

void pcl::OpenNIGrabber::startSynchronization ( )
protected

Start synchronization.

virtual void pcl::OpenNIGrabber::stop ( )
virtual

Stop the data acquisition.

Implements pcl::Grabber.

void pcl::OpenNIGrabber::stopSynchronization ( )
protected

Stop synchronization.

void pcl::OpenNIGrabber::updateModeMaps ( )
protected

Update mode maps.

Member Data Documentation

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

Definition at line 464 of file openni_grabber.h.

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

Definition at line 474 of file openni_grabber.h.

unsigned pcl::OpenNIGrabber::depth_buffer_size_
mutableprotected

Definition at line 472 of file openni_grabber.h.

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

Definition at line 466 of file openni_grabber.h.

double pcl::OpenNIGrabber::depth_focal_length_x_
protected

The depth image focal length (fx).

Definition at line 486 of file openni_grabber.h.

double pcl::OpenNIGrabber::depth_focal_length_y_
protected

The depth image focal length (fy).

Definition at line 488 of file openni_grabber.h.

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

Definition at line 424 of file openni_grabber.h.

unsigned pcl::OpenNIGrabber::depth_height_
protected

Definition at line 428 of file openni_grabber.h.

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

Definition at line 436 of file openni_grabber.h.

double pcl::OpenNIGrabber::depth_principal_point_x_
protected

The depth image principal point (cx).

Definition at line 490 of file openni_grabber.h.

double pcl::OpenNIGrabber::depth_principal_point_y_
protected

The depth image principal point (cy).

Definition at line 492 of file openni_grabber.h.

bool pcl::OpenNIGrabber::depth_required_
protected

Definition at line 431 of file openni_grabber.h.

unsigned pcl::OpenNIGrabber::depth_width_
protected

Definition at line 427 of file openni_grabber.h.

boost::shared_ptr<openni_wrapper::OpenNIDevice> pcl::OpenNIGrabber::device_
protected

The actual openni device.

Definition at line 421 of file openni_grabber.h.

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

Definition at line 467 of file openni_grabber.h.

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.

unsigned pcl::OpenNIGrabber::image_height_
protected

Definition at line 426 of file openni_grabber.h.

bool pcl::OpenNIGrabber::image_required_
protected

Definition at line 430 of file openni_grabber.h.

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

Definition at line 435 of file openni_grabber.h.

unsigned pcl::OpenNIGrabber::image_width_
protected

Definition at line 425 of file openni_grabber.h.

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

Definition at line 475 of file openni_grabber.h.

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

Definition at line 468 of file openni_grabber.h.

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.

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

Definition at line 437 of file openni_grabber.h.

bool pcl::OpenNIGrabber::ir_required_
protected

Definition at line 432 of file openni_grabber.h.

Synchronizer<boost::shared_ptr<openni_wrapper::IRImage>, boost::shared_ptr<openni_wrapper::DepthImage> > pcl::OpenNIGrabber::ir_sync_
protected

Definition at line 418 of file openni_grabber.h.

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.

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.

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.

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

Definition at line 440 of file openni_grabber.h.

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

Definition at line 473 of file openni_grabber.h.

unsigned pcl::OpenNIGrabber::rgb_array_size_
mutableprotected

Definition at line 471 of file openni_grabber.h.

double pcl::OpenNIGrabber::rgb_focal_length_x_
protected

The RGB image focal length (fx).

Definition at line 478 of file openni_grabber.h.

double pcl::OpenNIGrabber::rgb_focal_length_y_
protected

The RGB image focal length (fy).

Definition at line 480 of file openni_grabber.h.

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

Definition at line 423 of file openni_grabber.h.

double pcl::OpenNIGrabber::rgb_principal_point_x_
protected

The RGB image principal point (cx).

Definition at line 482 of file openni_grabber.h.

double pcl::OpenNIGrabber::rgb_principal_point_y_
protected

The RGB image principal point (cy).

Definition at line 484 of file openni_grabber.h.

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

Definition at line 417 of file openni_grabber.h.

bool pcl::OpenNIGrabber::running_
protected

Definition at line 469 of file openni_grabber.h.

bool pcl::OpenNIGrabber::sync_required_
protected

Definition at line 433 of file openni_grabber.h.


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