Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #include <jsk_topic_tools/log_utils.h>
00037 #include "jsk_pcl_ros/pointcloud_database_server.h"
00038 #include <jsk_topic_tools/rosparam_utils.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/io/vtk_lib_io.h>
00041 #include "jsk_recognition_utils/pcl_conversion_util.h"
00042 
00043 namespace jsk_pcl_ros
00044 {
00045 
00046   PointCloudData::PointCloudData(const std::string fname):
00047     file_name_(fname)
00048   {
00049     cloud_.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
00050     boost::filesystem::path path(file_name_);
00051     ext_ = path.extension().string();
00052     stem_ = path.stem().string();
00053     if (ext_ == ".stl") 
00054     {
00055       pcl::io::loadPolygonFileSTL(file_name_, mesh_);
00056       pcl::fromPCLPointCloud2(mesh_.cloud, *cloud_);
00057     }
00058     else
00059     {
00060       pcl::io::loadPCDFile(file_name_, *cloud_);
00061     }
00062   }
00063 
00064   pcl::PointCloud<pcl::PointXYZRGB>::Ptr PointCloudData::getPointCloud()
00065   {
00066   return cloud_;
00067   }
00068 
00069   sensor_msgs::PointCloud2
00070   PointCloudData::getROSPointCloud(ros::Time stamp)
00071   {
00072     sensor_msgs::PointCloud2 ros_out;
00073     pcl::toROSMsg(*cloud_, ros_out);
00074     ros_out.header.stamp = stamp;
00075     ros_out.header.frame_id = stem_;
00076     return ros_out;
00077   }
00078 
00079   PointcloudDatabaseServer::~PointcloudDatabaseServer()
00080   {
00081     timer_.stop();
00082   }
00083 
00084   void PointcloudDatabaseServer::onInit()
00085   {
00086     PCLNodelet::onInit();
00087     pub_points_array_ = pnh_->advertise<jsk_recognition_msgs::PointsArray>("output", 1);
00088     pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>("cloud", 1);
00089     if (!jsk_topic_tools::readVectorParameter(*pnh_, "models", files_)
00090         || files_.size() == 0) {
00091       NODELET_FATAL("no models is specified");
00092       return;
00093     }
00094 
00095     for (size_t i = 0; i< files_.size(); i++) {
00096       PointCloudData::Ptr data(new PointCloudData(files_[i]));
00097       point_clouds_.push_back(data);
00098       array_msg_.cloud_list.push_back(point_clouds_[i]->getROSPointCloud(ros::Time::now()));
00099     }
00100     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00101     dynamic_reconfigure::Server<Config>::CallbackType f =
00102       boost::bind(
00103         &PointcloudDatabaseServer::configCallback, this, _1, _2);
00104     srv_->setCallback (f);
00105     pnh_->getParam("duration", duration_);
00106   }
00107 
00108   void PointcloudDatabaseServer::timerCallback(const ros::TimerEvent& event)
00109   {
00110     if (use_array_) {
00111       for (size_t i = 0; i< files_.size(); i++) {
00112         array_msg_.cloud_list[i].header.stamp = event.current_real;
00113       }
00114       array_msg_.header.stamp = event.current_real;
00115       pub_points_array_.publish(array_msg_);
00116    } else {
00117       point_msg_ = point_clouds_[0]->getROSPointCloud(event.current_real);
00118       point_msg_.header.stamp = event.current_real;
00119       pub_cloud_.publish(point_msg_);
00120     }
00121   }
00122 
00123   void PointcloudDatabaseServer::configCallback(Config &config, uint32_t level)
00124   {
00125     boost::mutex::scoped_lock lock(mutex_);
00126     duration_ = config.duration;
00127     use_array_ = config.use_array;
00128     if (timer_) {
00129       timer_.stop();
00130     }
00131     timer_ = pnh_->createTimer(ros::Duration(duration_),
00132                                boost::bind(
00133                                            &PointcloudDatabaseServer::timerCallback,
00134                                            this,
00135                                            _1));
00136   }
00137 }
00138 
00139 #include <pluginlib/class_list_macros.h>
00140 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PointcloudDatabaseServer,
00141                         nodelet::Nodelet);