Point Cloud Library (PCL)
1.14.1-dev
|
Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live) More...
#include <pcl/io/openni_grabber.h>
Classes | |
struct | modeComp |
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... | |
Grabber & | operator= (const Grabber &)=delete |
No copy assign operator since Grabber can't be copied. More... | |
Grabber (Grabber &&)=default | |
Move ctor. More... | |
Grabber & | operator= (Grabber &&)=default |
Move assign operator. More... | |
virtual | ~Grabber () noexcept=default |
virtual destructor. More... | |
template<typename T > | |
boost::signals2::connection | registerCallback (const std::function< T > &callback) |
registers a callback function/method to a signal with the corresponding signature More... | |
template<typename T > | |
bool | providesCallback () const noexcept |
indicates whether a signal with given parameter-type exists or not More... | |
bool | toggle () |
For devices that are streaming, stopped streams are started and running stream are stopped. More... | |
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 () |
Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live)
Definition at line 69 of file openni_grabber.h.
using pcl::OpenNIGrabber::ConstPtr = shared_ptr<const OpenNIGrabber> |
Definition at line 73 of file openni_grabber.h.
using pcl::OpenNIGrabber::Ptr = shared_ptr<OpenNIGrabber> |
Definition at line 72 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_depth_image = void (const openni_wrapper::DepthImage::Ptr &) |
Definition at line 91 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_image = void (const openni_wrapper::Image::Ptr &) |
Definition at line 90 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_image_depth_image = void (const openni_wrapper::Image::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) |
Definition at line 93 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_ir_depth_image = void (const openni_wrapper::IRImage::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) |
Definition at line 94 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_ir_image = void (const openni_wrapper::IRImage::Ptr &) |
Definition at line 92 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_point_cloud = void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &) |
Definition at line 95 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_point_cloud_i = void (const pcl::PointCloud<pcl::PointXYZI>::ConstPtr &) |
Definition at line 98 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb = void (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &) |
Definition at line 96 of file openni_grabber.h.
using pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba = void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &) |
Definition at line 97 of file openni_grabber.h.
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.
pcl::OpenNIGrabber::OpenNIGrabber | ( | const std::string & | device_id = "" , |
const Mode & | depth_mode = OpenNI_Default_Mode , |
||
const Mode & | image_mode = OpenNI_Default_Mode |
||
) |
Constructor.
[in] | device_id | ID of the device, which might be a serial number, bus@address or the index of the device. |
[in] | depth_mode | the mode of the depth stream |
[in] | image_mode | the mode of the image stream |
|
overridenoexcept |
virtual Destructor inherited from the Grabber interface.
It never throws.
|
protectedvirtual |
Check if the depth stream is required or not.
|
protectedvirtual |
Check if the RGB and Depth images are required to be synchronized or not.
|
protectedvirtual |
Check if the RGB image stream is required or not.
|
protectedvirtual |
Check if the IR image stream is required or not.
|
inline |
Convert vector of raw shift values to depth values.
[in] | shift_data_ptr | input shift data |
[out] | depth_data_ptr | generated depth data |
[in] | size | of shift and depth buffer |
Definition at line 300 of file openni_grabber.h.
|
protected |
Convert a Depth + Intensity image pair to a pcl::PointCloud<pcl::PointXYZI>
[in] | image | the IR image to convert |
[in] | depth_image | the depth image to convert |
|
protected |
Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>
[in] | depth | the depth image to convert |
|
protected |
|
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.
|
inline |
Get the Depth camera parameters (fx, fy, cx, cy)
[out] | depth_focal_length_x | the Depth focal length (fx) |
[out] | depth_focal_length_y | the Depth focal length (fy) |
[out] | depth_principal_point_x | the Depth principal point (cx) |
[out] | depth_principal_point_y | the Depth principal point (cy) |
Definition at line 247 of file openni_grabber.h.
|
inline |
Return the Depth focal length parameters (fx, fy)
[out] | depth_focal_length_x | the Depth focal length (fx) |
[out] | depth_focal_length_y | the Depth focal length (fy) |
Definition at line 288 of file openni_grabber.h.
|
inline |
Get a pcl::shared pointer to the openni_wrapper::OpenNIDevice object.
Definition at line 496 of file openni_grabber.h.
References device_.
|
overridevirtual |
Obtain the number of frames per second (FPS).
Implements pcl::Grabber.
|
overridevirtual |
returns the name of the concrete subclass.
Implements pcl::Grabber.
|
inline |
Get the RGB camera parameters (fx, fy, cx, cy)
[out] | rgb_focal_length_x | the RGB focal length (fx) |
[out] | rgb_focal_length_y | the RGB focal length (fy) |
[out] | rgb_principal_point_x | the RGB principal point (cx) |
[out] | rgb_principal_point_y | the RGB principal point (cy) |
Definition at line 171 of file openni_grabber.h.
|
inline |
Return the RGB focal length parameters (fx, fy)
[out] | rgb_focal_length_x | the RGB focal length (fx) |
[out] | rgb_focal_length_y | the RGB focal length (fy) |
Definition at line 214 of file openni_grabber.h.
|
protectedvirtual |
RGB image callback.
|
protectedvirtual |
RGB + Depth image callback.
|
protectedvirtual |
IR image callback.
|
protectedvirtual |
IR + Depth image callback.
|
overridevirtual |
Check if the data acquisition is still running.
Implements pcl::Grabber.
|
protected |
Map config modes.
|
protected |
On initialization processing.
|
inline |
Set the Depth camera parameters (fx, fy, cx, cy)
[in] | depth_focal_length_x | the Depth focal length (fx) |
[in] | depth_focal_length_y | the Depth focal length (fy) |
[in] | depth_principal_point_x | the Depth principal point (cx) |
[in] | depth_principal_point_y | the 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.
|
inline |
Set the Depth image focal length (fx = fy).
[in] | depth_focal_length | the 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.
|
inline |
Set the Depth image focal length.
[in] | depth_focal_length_x | the Depth focal length (fx) |
[in] | depth_focal_length_y | the 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.
|
inline |
Set the RGB camera parameters (fx, fy, cx, cy)
[in] | rgb_focal_length_x | the RGB focal length (fx) |
[in] | rgb_focal_length_y | the RGB focal length (fy) |
[in] | rgb_principal_point_x | the RGB principal point (cx) |
[in] | rgb_principal_point_y | the 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.
|
inline |
Set the RGB image focal length (fx = fy).
[in] | rgb_focal_length | the 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.
|
inline |
Set the RGB image focal length.
[in] | rgb_focal_length_x | the RGB focal length (fx) |
[in] | rgb_focal_length_y | the 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.
|
protected |
Sets up an OpenNI device.
|
overrideprotectedvirtual |
Process changed signals.
Reimplemented from pcl::Grabber.
|
overridevirtual |
Start the data acquisition.
Implements pcl::Grabber.
|
protected |
Start synchronization.
|
overridevirtual |
Stop the data acquisition.
Implements pcl::Grabber.
|
protected |
Stop synchronization.
|
protected |
Update mode maps.
|
protected |
Definition at line 461 of file openni_grabber.h.
|
mutableprotected |
Definition at line 471 of file openni_grabber.h.
|
mutableprotected |
Definition at line 469 of file openni_grabber.h.
|
protected |
Definition at line 463 of file openni_grabber.h.
|
protected |
The depth image focal length (fx).
Definition at line 483 of file openni_grabber.h.
|
protected |
The depth image focal length (fy).
Definition at line 485 of file openni_grabber.h.
|
protected |
Definition at line 424 of file openni_grabber.h.
|
protected |
Definition at line 428 of file openni_grabber.h.
|
protected |
Definition at line 436 of file openni_grabber.h.
|
protected |
The depth image principal point (cx).
Definition at line 487 of file openni_grabber.h.
|
protected |
The depth image principal point (cy).
Definition at line 489 of file openni_grabber.h.
|
protected |
Definition at line 431 of file openni_grabber.h.
|
protected |
Definition at line 427 of file openni_grabber.h.
|
protected |
The actual openni device.
Definition at line 421 of file openni_grabber.h.
Referenced by getDevice().
|
protected |
Definition at line 464 of file openni_grabber.h.
|
protected |
Definition at line 438 of file openni_grabber.h.
|
protected |
Definition at line 426 of file openni_grabber.h.
|
protected |
Definition at line 430 of file openni_grabber.h.
|
protected |
Definition at line 435 of file openni_grabber.h.
|
protected |
Definition at line 425 of file openni_grabber.h.
|
mutableprotected |
Definition at line 472 of file openni_grabber.h.
|
protected |
Definition at line 465 of file openni_grabber.h.
|
protected |
Definition at line 439 of file openni_grabber.h.
|
protected |
Definition at line 437 of file openni_grabber.h.
|
protected |
Definition at line 432 of file openni_grabber.h.
|
protected |
Definition at line 418 of file openni_grabber.h.
|
protected |
Definition at line 441 of file openni_grabber.h.
|
protected |
Definition at line 442 of file openni_grabber.h.
|
protected |
Definition at line 443 of file openni_grabber.h.
|
protected |
Definition at line 440 of file openni_grabber.h.
|
mutableprotected |
Definition at line 470 of file openni_grabber.h.
|
mutableprotected |
Definition at line 468 of file openni_grabber.h.
|
protected |
The RGB image focal length (fx).
Definition at line 475 of file openni_grabber.h.
|
protected |
The RGB image focal length (fy).
Definition at line 477 of file openni_grabber.h.
|
protected |
Definition at line 423 of file openni_grabber.h.
|
protected |
The RGB image principal point (cx).
Definition at line 479 of file openni_grabber.h.
|
protected |
The RGB image principal point (cy).
Definition at line 481 of file openni_grabber.h.
|
protected |
Definition at line 417 of file openni_grabber.h.
|
protected |
Definition at line 466 of file openni_grabber.h.
|
protected |
Definition at line 433 of file openni_grabber.h.