40#include <pcl/pcl_config.h>
42#include <pcl/common/io.h>
43#include <pcl/io/grabber.h>
44#include <pcl/io/file_grabber.h>
45#include <pcl/common/time_trigger.h>
46#include <pcl/conversions.h>
50#include <pcl/io/openni_camera/openni_image.h>
51#include <pcl/io/openni_camera/openni_image_rgb24.h>
52#include <pcl/io/openni_camera/openni_depth_image.h>
119 getCloudAt (std::
size_t idx,
160 size ()
const override;
164 publish (
const pcl::PCLPointCloud2&
blob,
const Eigen::Vector4f&
origin,
const Eigen::Quaternionf& orientation,
const std::string& file_name)
const override;
177 template<
typename Po
intT>
191 template<
typename Po
intT>
210 Eigen::Quaternionf orientation;
214 cloud->sensor_origin_ =
origin;
215 cloud->sensor_orientation_ = orientation;
220 template <
typename Po
intT> std::size_t
223 return (numFrames ());
227 template<
typename Po
intT>
void
232 cloud->sensor_origin_ =
origin;
233 cloud->sensor_orientation_ = orientation;
235 signal_->operator () (cloud);
236 if (file_name_signal_->num_slots() > 0)
237 file_name_signal_->operator()(file_name);
241 if (!cloud->isOrganized ())
248 for (std::uint32_t i = 0; i < cloud->height; ++i)
249 for (std::uint32_t j = 0; j < cloud->width; ++j)
256 if (depth_image_signal_->num_slots() > 0)
260 std::vector<pcl::PCLPointField> fields;
272 for (std::uint32_t i = 0; i < cloud->height; ++i)
274 for (std::uint32_t j = 0; j < cloud->width; ++j)
287 if (image_signal_->num_slots() > 0)
288 image_signal_->operator()(image);
290 if (image_depth_image_signal_->num_slots() > 0)
291 image_depth_image_signal_->operator()(image,
depth_image, 1.0f / 525.0f);
This class provides methods to fill a depth or disparity image.
pcl::shared_ptr< DepthImage > Ptr
pcl::shared_ptr< Image > Ptr
This class provides methods to fill a RGB or Grayscale image buffer from underlying RGB24 image.
Iterator class for point clouds with or without given indices.
ConstCloudIterator(const PointCloud< PointT > &cloud)
FileGrabber provides a container-style interface for grabbers which operate on fixed-size input.
Grabber interface for PCL 1.x device drivers.
boost::signals2::signal< T > * createSignal()
Base class for PCD file grabber.
PCDGrabberBase(const std::string &pcd_file, float frames_per_second, bool repeat)
Constructor taking just one PCD file or one TAR file containing multiple PCD files.
PCDGrabberBase(const std::vector< std::string > &pcd_files, float frames_per_second, bool repeat)
Constructor taking a list of paths to PCD files, that are played in the order they appear in the list...
~PCDGrabberBase() noexcept
Virtual destructor.
boost::signals2::signal< void(const openni_wrapper::Image::Ptr &)> image_signal_)
boost::signals2::signal< void(const openni_wrapper::DepthImage::Ptr &)> depth_image_signal_)
const pcl::PointCloud< PointT >::ConstPtr operator[](std::size_t idx) const override
operator[] Returns the idx-th cloud in the dataset, without bounds checking.
boost::signals2::signal< void(const openni_wrapper::Image::Ptr &, const openni_wrapper::DepthImage::Ptr &, float constant)> image_depth_image_signal_)
boost::signals2::signal< void(const typename pcl::PointCloud< PointT >::ConstPtr &)> signal_)
PCDGrabber(const std::string &pcd_path, float frames_per_second=0, bool repeat=false)
void publish(const pcl::PCLPointCloud2 &blob, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, const std::string &file_name) const override
std::size_t size() const override
size Returns the number of clouds currently loaded by the grabber
~PCDGrabber() noexcept
Virtual destructor.
boost::signals2::signal< void(const std::string &)> file_name_signal_)
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
Defines functions, macros and traits for allocating and using memory.
void fromPCLPointCloud2(const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map)
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
A point structure representing Euclidean xyz coordinates, and the RGB color.
A structure representing RGB color information.