Point Cloud Library (PCL) 1.12.1
|
Grabber for Intel Realsense 2 SDK devices (D400 series) More...
#include <pcl/io/real_sense_2_grabber.h>
Public Types | |
typedef void() | signal_librealsense_PointXYZ(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) |
typedef void() | signal_librealsense_PointXYZI(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) |
typedef void() | signal_librealsense_PointXYZRGB(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &) |
typedef void() | signal_librealsense_PointXYZRGBA(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 () | |
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... | |
![]() | |
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... | |
virtual void | start ()=0 |
For devices that are streaming, the streams are started by calling this method. More... | |
virtual void | stop ()=0 |
For devices that are streaming, the streams are stopped. More... | |
bool | toggle () |
For devices that are streaming, stopped streams are started and running stream are stopped. More... | |
virtual std::string | getName () const =0 |
returns the name of the concrete subclass. More... | |
virtual bool | isRunning () const =0 |
Indicates whether the grabber is streaming or not. More... | |
virtual float | getFramesPerSecond () const =0 |
returns fps. 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... | |
![]() | |
virtual void | signalsChanged () |
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_ |
controlling the state of the thread. More... | |
bool | running_ |
Is the grabber running. More... | |
float | fps_ |
Calculated FPS for the grabber. More... | |
std::uint32_t | device_width_ |
Width for the depth and color sensor. More... | |
std::uint32_t | device_height_ |
Height for the depth and color sensor. More... | |
std::uint32_t | target_fps_ |
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... | |
![]() | |
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_ |
Grabber for Intel Realsense 2 SDK devices (D400 series)
Definition at line 59 of file real_sense_2_grabber.h.
typedef void() pcl::RealSense2Grabber::signal_librealsense_PointXYZ(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) |
Definition at line 107 of file real_sense_2_grabber.h.
typedef void() pcl::RealSense2Grabber::signal_librealsense_PointXYZI(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) |
Definition at line 108 of file real_sense_2_grabber.h.
typedef void() pcl::RealSense2Grabber::signal_librealsense_PointXYZRGB(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &) |
Definition at line 109 of file real_sense_2_grabber.h.
typedef void() pcl::RealSense2Grabber::signal_librealsense_PointXYZRGBA(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &) |
Definition at line 110 of file real_sense_2_grabber.h.
pcl::RealSense2Grabber::RealSense2Grabber | ( | const std::string & | file_name_or_serial_number = "" , |
const bool | repeat_playback = true |
||
) |
Constructor.
[in] | file_name_or_serial_number | used for either loading bag file or specific device by serial number |
[in] | repeat_playback | whether to repeat playback when reading from file |
pcl::RealSense2Grabber::~RealSense2Grabber | ( | ) |
virtual Destructor inherited from the Grabber interface.
It never throws.
|
protected |
Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>
[in] | points | the depth points |
|
protected |
Convert an Infrared Depth image to a pcl::PointCloud<pcl::PointXYZI>
[in] | points | the depth points |
[in] | ir | Infrared video frame |
|
protected |
template function to convert realsense point cloud to PCL point cloud
[in] | points | - realsense point cloud array |
[in] | mapColorFunc | dynamic function to convert individual point color or intensity values |
|
protected |
Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGBA>
[in] | points | the depth points |
[in] | rgb | rgb video frame |
|
protected |
Convert an rgb Depth image to a pcl::PointCloud<pcl::PointXYZRGB>
[in] | points | the depth points |
[in] | rgb | rgb video frame |
|
overridevirtual |
Obtain the number of frames per second (FPS).
Implements pcl::Grabber.
|
inlineoverridevirtual |
defined grabber name
Implements pcl::Grabber.
Definition at line 104 of file real_sense_2_grabber.h.
|
staticprotected |
Retrieve RGB color from texture video frame.
[in] | texture | the texture |
[in] | u | 2D coordinate |
[in] | v | 2D coordinate |
|
staticprotected |
Retrieve pixel index for UV texture coordinate.
[in] | texture | the texture |
[in] | u | 2D coordinate |
[in] | v | 2D coordinate |
|
staticprotected |
Retrieve color intensity from texture video frame.
[in] | texture | the texture |
[in] | u | 2D coordinate |
[in] | v | 2D coordinate |
|
overridevirtual |
Check if the data acquisition is still running.
Implements pcl::Grabber.
|
protected |
Dynamic reinitialization.
|
inline |
Set the device options.
[in] | width | resolution |
[in] | height | resolution |
[in] | fps | target frames per second for the device |
Definition at line 77 of file real_sense_2_grabber.h.
|
overrideprotectedvirtual |
Handle when a signal callback has been changed.
Reimplemented from pcl::Grabber.
|
overridevirtual |
Start the data acquisition.
Implements pcl::Grabber.
|
overridevirtual |
Stop the data acquisition.
Implements pcl::Grabber.
|
protected |
the thread function
|
protected |
Height for the depth and color sensor.
Default 240
Definition at line 209 of file real_sense_2_grabber.h.
|
protected |
Width for the depth and color sensor.
Default 424
Definition at line 207 of file real_sense_2_grabber.h.
|
protected |
Defines either a file path to a bag file or a realsense device serial number.
Definition at line 197 of file real_sense_2_grabber.h.
|
protected |
Calculated FPS for the grabber.
Definition at line 205 of file real_sense_2_grabber.h.
|
protected |
Declare pointcloud object, for calculating pointclouds and texture mappings.
Definition at line 213 of file real_sense_2_grabber.h.
|
protected |
Declare RealSense pipeline, encapsulating the actual device and sensors.
Definition at line 215 of file real_sense_2_grabber.h.
|
protected |
controlling the state of the thread.
Definition at line 201 of file real_sense_2_grabber.h.
|
protected |
Repeat playback when reading from file.
Definition at line 199 of file real_sense_2_grabber.h.
|
protected |
Is the grabber running.
Definition at line 203 of file real_sense_2_grabber.h.
|
protected |
Definition at line 114 of file real_sense_2_grabber.h.
|
protected |
Definition at line 115 of file real_sense_2_grabber.h.
|
protected |
Definition at line 116 of file real_sense_2_grabber.h.
|
protected |
Definition at line 117 of file real_sense_2_grabber.h.
|
protected |
|
protected |
handle to the thread
Definition at line 195 of file real_sense_2_grabber.h.