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

Grabber for Intel Realsense 2 SDK devices (D400 series) More...

#include <pcl/io/real_sense_2_grabber.h>

+ Inheritance diagram for pcl::RealSense2Grabber:
+ Collaboration diagram for pcl::RealSense2Grabber:

Public Types

using signal_librealsense_PointXYZ = void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &)
 
using signal_librealsense_PointXYZI = void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &)
 
using signal_librealsense_PointXYZRGB = void(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &)
 
using signal_librealsense_PointXYZRGBA = void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &)
 

Public Member Functions

 RealSense2Grabber (const std::string &file_name_or_serial_number="", const bool repeat_playback=true)
 Constructor. More...
 
 ~RealSense2Grabber () override
 virtual Destructor inherited from the Grabber interface. More...
 
void setDeviceOptions (std::uint32_t width, std::uint32_t height, std::uint32_t fps=30)
 Set the device options. 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...
 
float getFramesPerSecond () const override
 Obtain the number of frames per second (FPS). More...
 
std::string getName () const override
 defined grabber name 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 signalsChanged () override
 Handle when a signal callback has been changed. More...
 
void threadFunction ()
 the thread function More...
 
void reInitialize ()
 Dynamic reinitialization. More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr convertDepthToPointXYZ (const rs2::points &points)
 Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ> More...
 
pcl::PointCloud< pcl::PointXYZI >::Ptr convertIntensityDepthToPointXYZRGBI (const rs2::points &points, const rs2::video_frame &ir)
 Convert an Infrared Depth image to a pcl::PointCloud<pcl::PointXYZI> More...
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr convertRGBDepthToPointXYZRGB (const rs2::points &points, const rs2::video_frame &rgb)
 Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGB> More...
 
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr convertRGBADepthToPointXYZRGBA (const rs2::points &points, const rs2::video_frame &rgb)
 Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGBA> More...
 
template<typename PointT , typename Functor >
pcl::PointCloud< PointT >::Ptr convertRealsensePointsToPointCloud (const rs2::points &points, Functor mapColorFunc)
 template function to convert realsense point cloud to PCL point cloud 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 ()
 

Static Protected Member Functions

static size_t getTextureIdx (const rs2::video_frame &texture, float u, float v)
 Retrieve pixel index for UV texture coordinate. More...
 
static pcl::RGB getTextureColor (const rs2::video_frame &texture, float u, float v)
 Retrieve RGB color from texture video frame. More...
 
static std::uint8_t getTextureIntensity (const rs2::video_frame &texture, float u, float v)
 Retrieve color intensity from texture video frame. More...
 

Protected Attributes

boost::signals2::signal< signal_librealsense_PointXYZ > * signal_PointXYZ
 
boost::signals2::signal< signal_librealsense_PointXYZI > * signal_PointXYZI
 
boost::signals2::signal< signal_librealsense_PointXYZRGB > * signal_PointXYZRGB
 
boost::signals2::signal< signal_librealsense_PointXYZRGBA > * signal_PointXYZRGBA
 
std::thread thread_
 handle to the thread More...
 
std::string file_name_or_serial_number_
 Defines either a file path to a bag file or a realsense device serial number. More...
 
bool repeat_playback_
 Repeat playback when reading from file. More...
 
bool quit_ {false}
 controlling the state of the thread. More...
 
bool running_ {false}
 Is the grabber running. More...
 
float fps_ {0.0f}
 Calculated FPS for the grabber. More...
 
std::uint32_t device_width_ {424}
 Width for the depth and color sensor. More...
 
std::uint32_t device_height_ {240}
 Height for the depth and color sensor. More...
 
std::uint32_t target_fps_ {30}
 Target FPS for the device. More...
 
rs2::pointcloud pc_
 Declare pointcloud object, for calculating pointclouds and texture mappings. More...
 
rs2::pipeline pipe_
 Declare RealSense pipeline, encapsulating the actual device and sensors. 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 Intel Realsense 2 SDK devices (D400 series)

Note
Device width/height defaults to 424/240, the lowest resolutions for D400 devices.
Testing on the in_hand_scanner example we found the lower default resolution allowed the app to perform adequately.
Developers should use this resolution as a starting point and gradually increase to get the best results
Author
Patrick Abadi patri.nosp@m.ckab.nosp@m.adi@g.nosp@m.mail.nosp@m..com, Daniel Packard pack3.nosp@m.754@.nosp@m.gmail.nosp@m..com

Definition at line 59 of file real_sense_2_grabber.h.

Member Typedef Documentation

◆ signal_librealsense_PointXYZ

Definition at line 108 of file real_sense_2_grabber.h.

◆ signal_librealsense_PointXYZI

Definition at line 109 of file real_sense_2_grabber.h.

◆ signal_librealsense_PointXYZRGB

Definition at line 110 of file real_sense_2_grabber.h.

◆ signal_librealsense_PointXYZRGBA

Definition at line 111 of file real_sense_2_grabber.h.

Constructor & Destructor Documentation

◆ RealSense2Grabber()

pcl::RealSense2Grabber::RealSense2Grabber ( const std::string &  file_name_or_serial_number = "",
const bool  repeat_playback = true 
)

Constructor.

Parameters
[in]file_name_or_serial_numberused for either loading bag file or specific device by serial number
[in]repeat_playbackwhether to repeat playback when reading from file

◆ ~RealSense2Grabber()

pcl::RealSense2Grabber::~RealSense2Grabber ( )
override

virtual Destructor inherited from the Grabber interface.

It never throws.

Member Function Documentation

◆ convertDepthToPointXYZ()

pcl::PointCloud<pcl::PointXYZ>::Ptr pcl::RealSense2Grabber::convertDepthToPointXYZ ( const rs2::points &  points)
protected

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

Parameters
[in]pointsthe depth points

◆ convertIntensityDepthToPointXYZRGBI()

pcl::PointCloud<pcl::PointXYZI>::Ptr pcl::RealSense2Grabber::convertIntensityDepthToPointXYZRGBI ( const rs2::points &  points,
const rs2::video_frame &  ir 
)
protected

Convert an Infrared Depth image to a pcl::PointCloud<pcl::PointXYZI>

Parameters
[in]pointsthe depth points
[in]irInfrared video frame

◆ convertRealsensePointsToPointCloud()

template<typename PointT , typename Functor >
pcl::PointCloud<PointT>::Ptr pcl::RealSense2Grabber::convertRealsensePointsToPointCloud ( const rs2::points &  points,
Functor  mapColorFunc 
)
protected

template function to convert realsense point cloud to PCL point cloud

Parameters
[in]points- realsense point cloud array
[in]mapColorFuncdynamic function to convert individual point color or intensity values

◆ convertRGBADepthToPointXYZRGBA()

pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pcl::RealSense2Grabber::convertRGBADepthToPointXYZRGBA ( const rs2::points &  points,
const rs2::video_frame &  rgb 
)
protected

Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGBA>

Parameters
[in]pointsthe depth points
[in]rgbrgb video frame

◆ convertRGBDepthToPointXYZRGB()

pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl::RealSense2Grabber::convertRGBDepthToPointXYZRGB ( const rs2::points &  points,
const rs2::video_frame &  rgb 
)
protected

Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGB>

Parameters
[in]pointsthe depth points
[in]rgbrgb video frame

◆ getFramesPerSecond()

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

Obtain the number of frames per second (FPS).

Implements pcl::Grabber.

◆ getName()

std::string pcl::RealSense2Grabber::getName ( ) const
inlineoverridevirtual

defined grabber name

Implements pcl::Grabber.

Definition at line 104 of file real_sense_2_grabber.h.

◆ getTextureColor()

static pcl::RGB pcl::RealSense2Grabber::getTextureColor ( const rs2::video_frame &  texture,
float  u,
float  v 
)
staticprotected

Retrieve RGB color from texture video frame.

Parameters
[in]texturethe texture
[in]u2D coordinate
[in]v2D coordinate

◆ getTextureIdx()

static size_t pcl::RealSense2Grabber::getTextureIdx ( const rs2::video_frame &  texture,
float  u,
float  v 
)
staticprotected

Retrieve pixel index for UV texture coordinate.

Parameters
[in]texturethe texture
[in]u2D coordinate
[in]v2D coordinate

◆ getTextureIntensity()

static std::uint8_t pcl::RealSense2Grabber::getTextureIntensity ( const rs2::video_frame &  texture,
float  u,
float  v 
)
staticprotected

Retrieve color intensity from texture video frame.

Parameters
[in]texturethe texture
[in]u2D coordinate
[in]v2D coordinate

◆ isRunning()

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

Check if the data acquisition is still running.

Implements pcl::Grabber.

◆ reInitialize()

void pcl::RealSense2Grabber::reInitialize ( )
protected

Dynamic reinitialization.

◆ setDeviceOptions()

void pcl::RealSense2Grabber::setDeviceOptions ( std::uint32_t  width,
std::uint32_t  height,
std::uint32_t  fps = 30 
)
inline

Set the device options.

Parameters
[in]widthresolution
[in]heightresolution
[in]fpstarget frames per second for the device

Definition at line 77 of file real_sense_2_grabber.h.

◆ signalsChanged()

void pcl::RealSense2Grabber::signalsChanged ( )
overrideprotectedvirtual

Handle when a signal callback has been changed.

Reimplemented from pcl::Grabber.

◆ start()

void pcl::RealSense2Grabber::start ( )
overridevirtual

Start the data acquisition.

Implements pcl::Grabber.

◆ stop()

void pcl::RealSense2Grabber::stop ( )
overridevirtual

Stop the data acquisition.

Implements pcl::Grabber.

◆ threadFunction()

void pcl::RealSense2Grabber::threadFunction ( )
protected

the thread function

Member Data Documentation

◆ device_height_

std::uint32_t pcl::RealSense2Grabber::device_height_ {240}
protected

Height for the depth and color sensor.

Default 240

Definition at line 210 of file real_sense_2_grabber.h.

◆ device_width_

std::uint32_t pcl::RealSense2Grabber::device_width_ {424}
protected

Width for the depth and color sensor.

Default 424

Definition at line 208 of file real_sense_2_grabber.h.

◆ file_name_or_serial_number_

std::string pcl::RealSense2Grabber::file_name_or_serial_number_
protected

Defines either a file path to a bag file or a realsense device serial number.

Definition at line 198 of file real_sense_2_grabber.h.

◆ fps_

float pcl::RealSense2Grabber::fps_ {0.0f}
protected

Calculated FPS for the grabber.

Definition at line 206 of file real_sense_2_grabber.h.

◆ pc_

rs2::pointcloud pcl::RealSense2Grabber::pc_
protected

Declare pointcloud object, for calculating pointclouds and texture mappings.

Definition at line 214 of file real_sense_2_grabber.h.

◆ pipe_

rs2::pipeline pcl::RealSense2Grabber::pipe_
protected

Declare RealSense pipeline, encapsulating the actual device and sensors.

Definition at line 216 of file real_sense_2_grabber.h.

◆ quit_

bool pcl::RealSense2Grabber::quit_ {false}
protected

controlling the state of the thread.

Definition at line 202 of file real_sense_2_grabber.h.

◆ repeat_playback_

bool pcl::RealSense2Grabber::repeat_playback_
protected

Repeat playback when reading from file.

Definition at line 200 of file real_sense_2_grabber.h.

◆ running_

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

Is the grabber running.

Definition at line 204 of file real_sense_2_grabber.h.

◆ signal_PointXYZ

boost::signals2::signal<signal_librealsense_PointXYZ>* pcl::RealSense2Grabber::signal_PointXYZ
protected

Definition at line 115 of file real_sense_2_grabber.h.

◆ signal_PointXYZI

boost::signals2::signal<signal_librealsense_PointXYZI>* pcl::RealSense2Grabber::signal_PointXYZI
protected

Definition at line 116 of file real_sense_2_grabber.h.

◆ signal_PointXYZRGB

boost::signals2::signal<signal_librealsense_PointXYZRGB>* pcl::RealSense2Grabber::signal_PointXYZRGB
protected

Definition at line 117 of file real_sense_2_grabber.h.

◆ signal_PointXYZRGBA

boost::signals2::signal<signal_librealsense_PointXYZRGBA>* pcl::RealSense2Grabber::signal_PointXYZRGBA
protected

Definition at line 118 of file real_sense_2_grabber.h.

◆ target_fps_

std::uint32_t pcl::RealSense2Grabber::target_fps_ {30}
protected

Target FPS for the device.

Default 30.

Definition at line 212 of file real_sense_2_grabber.h.

◆ thread_

std::thread pcl::RealSense2Grabber::thread_
protected

handle to the thread

Definition at line 196 of file real_sense_2_grabber.h.


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