pointcloud_database_server_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
39 #include <pcl/io/pcd_io.h>
40 #include <pcl/io/vtk_lib_io.h>
42 
43 namespace jsk_pcl_ros
44 {
45 
46  PointCloudData::PointCloudData(const std::string fname):
47  file_name_(fname)
48  {
49  cloud_.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
50  boost::filesystem::path path(file_name_);
51  ext_ = path.extension().string();
52  stem_ = path.stem().string();
53  if (ext_ == ".stl")
54  {
55  pcl::io::loadPolygonFileSTL(file_name_, mesh_);
56  pcl::fromPCLPointCloud2(mesh_.cloud, *cloud_);
57  }
58  else
59  {
61  }
62  }
63 
64  pcl::PointCloud<pcl::PointXYZRGB>::Ptr PointCloudData::getPointCloud()
65  {
66  return cloud_;
67  }
68 
69  sensor_msgs::PointCloud2
71  {
72  sensor_msgs::PointCloud2 ros_out;
73  pcl::toROSMsg(*cloud_, ros_out);
74  ros_out.header.stamp = stamp;
75  ros_out.header.frame_id = stem_;
76  return ros_out;
77  }
78 
80  {
81  timer_.stop();
82  }
83 
85  {
86  PCLNodelet::onInit();
87  pub_points_array_ = pnh_->advertise<jsk_recognition_msgs::PointsArray>("output", 1);
88  pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("cloud", 1);
89  if (!jsk_topic_tools::readVectorParameter(*pnh_, "models", files_)
90  || files_.size() == 0) {
91  NODELET_FATAL("no models is specified");
92  return;
93  }
94 
95  for (size_t i = 0; i< files_.size(); i++) {
96  PointCloudData::Ptr data(new PointCloudData(files_[i]));
97  point_clouds_.push_back(data);
98  array_msg_.cloud_list.push_back(point_clouds_[i]->getROSPointCloud(ros::Time::now()));
99  }
100  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
101  dynamic_reconfigure::Server<Config>::CallbackType f =
102  boost::bind(
104  srv_->setCallback (f);
105  pnh_->getParam("duration", duration_);
106  }
107 
109  {
110  if (use_array_) {
111  for (size_t i = 0; i< files_.size(); i++) {
112  array_msg_.cloud_list[i].header.stamp = event.current_real;
113  }
114  array_msg_.header.stamp = event.current_real;
115  pub_points_array_.publish(array_msg_);
116  } else {
117  point_msg_ = point_clouds_[0]->getROSPointCloud(event.current_real);
118  point_msg_.header.stamp = event.current_real;
119  pub_cloud_.publish(point_msg_);
120  }
121  }
122 
123  void PointcloudDatabaseServer::configCallback(Config &config, uint32_t level)
124  {
125  boost::mutex::scoped_lock lock(mutex_);
126  duration_ = config.duration;
127  use_array_ = config.use_array;
128  if (timer_) {
129  timer_.stop();
130  }
131  timer_ = pnh_->createTimer(ros::Duration(duration_),
132  boost::bind(
134  this,
135  _1));
136  }
137 }
138 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PointcloudDatabaseServer, nodelet::Nodelet)
path
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getPointCloud()
virtual void timerCallback(const ros::TimerEvent &event)
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
virtual sensor_msgs::PointCloud2 getROSPointCloud(ros::Time stamp)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
jsk_pcl_ros::PointcloudDatabaseServerConfig Config
static Time now()
#define NODELET_FATAL(...)
boost::mutex mutex_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_
virtual void configCallback(Config &config, uint32_t level)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47