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/or 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 
36 #include <jsk_topic_tools/log_utils.h>
38 #include <jsk_topic_tools/rosparam_utils.h>
39 #include <pcl/io/pcd_io.h>
40 #include <pcl/io/vtk_lib_io.h>
42 #include <boost/filesystem.hpp>
43 
44 namespace jsk_pcl_ros
45 {
46 
47  PointCloudData::PointCloudData(const std::string fname):
48  file_name_(fname)
49  {
50  cloud_.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
51  boost::filesystem::path path(file_name_);
52  ext_ = path.extension().string();
53  stem_ = path.stem().string();
54  if (ext_ == ".stl")
55  {
56  pcl::io::loadPolygonFileSTL(file_name_, mesh_);
57  pcl::fromPCLPointCloud2(mesh_.cloud, *cloud_);
58  }
59  else
60  {
62  }
63  }
64 
65  pcl::PointCloud<pcl::PointXYZRGB>::Ptr PointCloudData::getPointCloud()
66  {
67  return cloud_;
68  }
69 
70  sensor_msgs::PointCloud2
72  {
73  sensor_msgs::PointCloud2 ros_out;
74  pcl::toROSMsg(*cloud_, ros_out);
75  ros_out.header.stamp = stamp;
76  ros_out.header.frame_id = stem_;
77  return ros_out;
78  }
79 
81  {
82  timer_.stop();
83  }
84 
86  {
87  PCLNodelet::onInit();
88  pub_points_array_ = pnh_->advertise<jsk_recognition_msgs::PointsArray>("output", 1);
89  pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("cloud", 1);
90  if (!jsk_topic_tools::readVectorParameter(*pnh_, "models", files_)
91  || files_.size() == 0) {
92  NODELET_FATAL("no models is specified");
93  return;
94  }
95 
96  for (size_t i = 0; i< files_.size(); i++) {
98  point_clouds_.push_back(data);
99  array_msg_.cloud_list.push_back(point_clouds_[i]->getROSPointCloud(ros::Time::now()));
100  }
101  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
102  dynamic_reconfigure::Server<Config>::CallbackType f =
103  boost::bind(
105  srv_->setCallback (f);
106  pnh_->getParam("duration", duration_);
107  }
108 
110  {
111  if (use_array_) {
112  for (size_t i = 0; i< files_.size(); i++) {
113  array_msg_.cloud_list[i].header.stamp = event.current_real;
114  }
115  array_msg_.header.stamp = event.current_real;
117  } else {
118  point_msg_ = point_clouds_[0]->getROSPointCloud(event.current_real);
119  point_msg_.header.stamp = event.current_real;
121  }
122  }
123 
124  void PointcloudDatabaseServer::configCallback(Config &config, uint32_t level)
125  {
126  boost::mutex::scoped_lock lock(mutex_);
127  duration_ = config.duration;
128  use_array_ = config.use_array;
129  if (timer_) {
130  timer_.stop();
131  }
132  timer_ = pnh_->createTimer(ros::Duration(duration_),
133  boost::bind(
135  this,
136  _1));
137  }
138 }
139 
jsk_pcl_ros::PointcloudDatabaseServer::use_array_
bool use_array_
Definition: pointcloud_database_server.h:124
jsk_pcl_ros::PointcloudDatabaseServer::array_msg_
jsk_recognition_msgs::PointsArray array_msg_
Definition: pointcloud_database_server.h:120
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PointcloudDatabaseServer, nodelet::Nodelet)
NODELET_FATAL
#define NODELET_FATAL(...)
jsk_pcl_ros::PointcloudDatabaseServer::~PointcloudDatabaseServer
virtual ~PointcloudDatabaseServer()
Definition: pointcloud_database_server_nodelet.cpp:112
jsk_pcl_ros::PointcloudDatabaseServer::mutex_
boost::mutex mutex_
Definition: pointcloud_database_server.h:115
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
nodelet_topic_tools::NodeletLazy::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
jsk_pcl_ros::PointcloudDatabaseServer::pub_cloud_
ros::Publisher pub_cloud_
Definition: pointcloud_database_server.h:117
boost::shared_ptr
i
int i
jsk_pcl_ros::PointcloudDatabaseServer::duration_
double duration_
Definition: pointcloud_database_server.h:123
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
jsk_pcl_ros::PointcloudDatabaseServer::files_
std::vector< std::string > files_
Definition: pointcloud_database_server.h:110
jsk_pcl_ros::PointcloudDatabaseServer::timerCallback
virtual void timerCallback(const ros::TimerEvent &event)
Definition: pointcloud_database_server_nodelet.cpp:141
ros::Timer::stop
void stop()
jsk_pcl_ros::PointCloudData
Definition: pointcloud_database_server.h:81
jsk_pcl_ros::PointcloudDatabaseServer::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: pointcloud_database_server.h:114
jsk_pcl_ros::PointcloudDatabaseServer::point_msg_
sensor_msgs::PointCloud2 point_msg_
Definition: pointcloud_database_server.h:121
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::PointcloudDatabaseServer
Definition: pointcloud_database_server.h:101
jsk_pcl_ros::PointCloudData::getPointCloud
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getPointCloud()
Definition: pointcloud_database_server_nodelet.cpp:97
class_list_macros.h
jsk_pcl_ros::PointCloudData::stem_
std::string stem_
Definition: pointcloud_database_server.h:128
pointcloud_database_server.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PointcloudDatabaseServer::timer_
ros::Timer timer_
Definition: pointcloud_database_server.h:118
dump_depth_error.data
data
Definition: dump_depth_error.py:11
jsk_pcl_ros::PointcloudDatabaseServer::point_clouds_
std::vector< PointCloudData::Ptr > point_clouds_
Definition: pointcloud_database_server.h:119
pcl::io::loadPCDFile
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
ros::TimerEvent
ros::TimerEvent::current_real
Time current_real
pcl_conversion_util.h
jsk_pcl_ros::PointcloudDatabaseServer::onInit
virtual void onInit()
Definition: pointcloud_database_server_nodelet.cpp:117
jsk_pcl_ros::PointCloudData::PointCloudData
PointCloudData(const std::string fname)
Definition: pointcloud_database_server_nodelet.cpp:79
jsk_pcl_ros::PointCloudData::ext_
std::string ext_
Definition: pointcloud_database_server.h:126
jsk_pcl_ros::PointCloudData::cloud_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_
Definition: pointcloud_database_server.h:129
jsk_pcl_ros::PointCloudData::file_name_
const std::string file_name_
Definition: pointcloud_database_server.h:125
nodelet::Nodelet
jsk_pcl_ros::PointCloudData::getROSPointCloud
virtual sensor_msgs::PointCloud2 getROSPointCloud(ros::Time stamp)
Definition: pointcloud_database_server_nodelet.cpp:103
ros::Time
dump_depth_error.f
f
Definition: dump_depth_error.py:39
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::PointcloudDatabaseServer::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: pointcloud_database_server_nodelet.cpp:156
config
config
ros::Duration
jsk_pcl_ros::PointCloudData::mesh_
pcl::PolygonMesh mesh_
Definition: pointcloud_database_server.h:127
jsk_pcl_ros::PointcloudDatabaseServer::pub_points_array_
ros::Publisher pub_points_array_
Definition: pointcloud_database_server.h:116
ros::Time::now
static Time now()


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45