Point Cloud Library (PCL)
1.11.1
|
43 #include <pcl/io/boost.h>
44 #include <pcl/io/grabber.h>
45 #include <pcl/point_cloud.h>
48 #include <librealsense2/rs.hpp>
66 RealSense2Grabber (
const std::string& file_name_or_serial_number =
"",
const bool repeat_playback =
true );
79 device_width_ = width;
80 device_height_ = height;
104 getName ()
const override {
return std::string (
"RealSense2Grabber" ); }
165 template <
typename Po
intT,
typename Functor>
boost::signals2::signal< signal_librealsense_PointXYZ > * signal_PointXYZ
Defines all the PCL implemented PointT point type structures.
boost::signals2::signal< signal_librealsense_PointXYZRGB > * signal_PointXYZRGB
boost::signals2::signal< signal_librealsense_PointXYZI > * signal_PointXYZI
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>
static size_t getTextureIdx(const rs2::video_frame &texture, float u, float v)
Retrieve pixel index for UV texture coordinate.
boost::signals2::signal< signal_librealsense_PointXYZRGBA > * signal_PointXYZRGBA
float fps_
Calculated FPS for the grabber.
bool quit_
controlling the state of the thread.
static std::uint8_t getTextureIntensity(const rs2::video_frame &texture, float u, float v)
Retrieve color intensity from texture video frame.
Grabber for Intel Realsense 2 SDK devices (D400 series)
std::uint32_t device_width_
Width for the depth and color sensor.
virtual ~RealSense2Grabber() noexcept
virtual Destructor inherited from the Grabber interface.
Grabber interface for PCL 1.x device drivers.
static pcl::RGB getTextureColor(const rs2::video_frame &texture, float u, float v)
Retrieve RGB color from texture video frame.
float getFramesPerSecond() const override
Obtain the number of frames per second (FPS).
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>
std::uint32_t device_height_
Height for the depth and color sensor.
Base functor all the models that need non linear optimization must define their own one and implement...
void reInitialize()
Dynamic reinitialization.
pcl::PointCloud< pcl::PointXYZ >::Ptr convertDepthToPointXYZ(const rs2::points &points)
Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>
A structure representing RGB color information.
pcl::PointCloud< PointT >::Ptr convertRealsensePointsToPointCloud(const rs2::points &points, Functor mapColorFunc)
template function to convert realsense point cloud to PCL point cloud
void start() override
Start the data acquisition.
rs2::pipeline pipe_
Declare RealSense pipeline, encapsulating the actual device and sensors.
void signalsChanged() override
Handle when a signal callback has been changed.
void threadFunction()
the thread function
RealSense2Grabber(const std::string &file_name_or_serial_number="", const bool repeat_playback=true)
Constructor.
shared_ptr< PointCloud< PointT > > Ptr
std::string getName() const override
defined grabber name
bool running_
Is the grabber running.
shared_ptr< const PointCloud< PointT > > ConstPtr
std::thread thread_
handle to the thread
std::string file_name_or_serial_number_
Defines either a file path to a bag file or a realsense device serial number.
bool isRunning() const override
Check if the data acquisition is still running.
bool repeat_playback_
Repeat playback when reading from file.
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>
rs2::pointcloud pc_
Declare pointcloud object, for calculating pointclouds and texture mappings.
void stop() override
Stop the data acquisition.
std::uint32_t target_fps_
Target FPS for the device.