Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added callback signal for filename of grabbed pcd file. #1354

Merged
merged 1 commit into from
Oct 7, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 8 additions & 3 deletions io/include/pcl/io/pcd_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ namespace pcl

private:
virtual void
publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const = 0;
publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation, const std::string& file_name) const = 0;

// to separate and hide the implementation from interface: PIMPL
struct PCDGrabberImpl;
Expand Down Expand Up @@ -175,9 +175,10 @@ namespace pcl
protected:

virtual void
publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const;
publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation, const std::string& file_name) const;

boost::signals2::signal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>* signal_;
boost::signals2::signal<void (const std::string&)>* file_name_signal_;

#ifdef HAVE_OPENNI
boost::signals2::signal<void (const boost::shared_ptr<openni_wrapper::DepthImage>&)>* depth_image_signal_;
Expand All @@ -192,6 +193,7 @@ namespace pcl
: PCDGrabberBase (pcd_path, frames_per_second, repeat)
{
signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>();
file_name_signal_ = createSignal<void (const std::string&)>();
#ifdef HAVE_OPENNI
depth_image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::DepthImage>&)> ();
image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::Image>&)> ();
Expand All @@ -205,6 +207,7 @@ namespace pcl
: PCDGrabberBase (pcd_files, frames_per_second, repeat), signal_ ()
{
signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>();
file_name_signal_ = createSignal<void (const std::string&)>();
#ifdef HAVE_OPENNI
depth_image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::DepthImage>&)> ();
image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::Image>&)> ();
Expand Down Expand Up @@ -236,14 +239,16 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointT> void
PCDGrabber<PointT>::publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const
PCDGrabber<PointT>::publish (const pcl::PCLPointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation, const std::string& file_name) const
{
typename pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT> ());
pcl::fromPCLPointCloud2 (blob, *cloud);
cloud->sensor_origin_ = origin;
cloud->sensor_orientation_ = orientation;

signal_->operator () (cloud);
if (file_name_signal_->num_slots() > 0)
file_name_signal_->operator()(file_name);

#ifdef HAVE_OPENNI
// If dataset is not organized, return
Expand Down
8 changes: 7 additions & 1 deletion io/src/pcd_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ struct pcl::PCDGrabberBase::PCDGrabberImpl
pcl::PCLPointCloud2 next_cloud_;
Eigen::Vector4f origin_;
Eigen::Quaternionf orientation_;
std::string next_file_name_;
bool valid_;

// TAR reading I/O
Expand Down Expand Up @@ -127,6 +128,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabbe
, next_cloud_ ()
, origin_ ()
, orientation_ ()
, next_file_name_ ()
, valid_ (false)
, tar_fd_ (-1)
, tar_offset_ (0)
Expand All @@ -136,6 +138,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabbe
{
pcd_files_.push_back (pcd_path);
pcd_iterator_ = pcd_files_.begin ();
next_file_name_ = *pcd_iterator_;
readAhead ();
}

Expand All @@ -151,6 +154,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabbe
, next_cloud_ ()
, origin_ ()
, orientation_ ()
, next_file_name_ ()
, valid_ (false)
, tar_fd_ (-1)
, tar_offset_ (0)
Expand All @@ -160,6 +164,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabbe
{
pcd_files_ = pcd_files;
pcd_iterator_ = pcd_files_.begin ();
next_file_name_ = *pcd_iterator_;
readAhead ();
}

Expand Down Expand Up @@ -210,6 +215,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::readAhead ()
}
}

next_file_name_ = *pcd_iterator_;
if (++pcd_iterator_ == pcd_files_.end () && repeat_)
pcd_iterator_ = pcd_files_.begin ();
}
Expand Down Expand Up @@ -288,7 +294,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::trigger ()
{
boost::mutex::scoped_lock read_ahead_lock(read_ahead_mutex_);
if (valid_)
grabber_.publish (next_cloud_,origin_,orientation_);
grabber_.publish (next_cloud_,origin_,orientation_, next_file_name_);

// use remaining time, if there is time left!
readAhead ();
Expand Down