pointcloud_database_server_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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 
00041 namespace jsk_pcl_ros
00042 {
00043 
00044   PointCloudData::PointCloudData(const std::string fname):
00045     file_name_(fname)
00046   {
00047     pcl::PCDReader reader;
00048     cloud_.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
00049     reader.read(file_name_, *cloud_);
00050   }
00051 
00052   pcl::PointCloud<pcl::PointXYZRGB>::Ptr PointCloudData::getPointCloud()
00053   {
00054   return cloud_;
00055   }
00056 
00057   sensor_msgs::PointCloud2
00058   PointCloudData::getROSPointCloud(ros::Time stamp)
00059   {
00060     sensor_msgs::PointCloud2 ros_out;
00061     ros_out.header.stamp = stamp;
00062     ros_out.header.frame_id = file_name_;
00063     pcl::toROSMsg(*cloud_, ros_out);
00064     return ros_out;
00065   }
00066 
00067   PointcloudDatabaseServer::~PointcloudDatabaseServer()
00068   {
00069     timer_.stop();
00070   }
00071 
00072   void PointcloudDatabaseServer::onInit()
00073   {
00074     PCLNodelet::onInit();
00075     std::vector<std::string> pcd_files;
00076     pub_points_ = pnh_->advertise<jsk_recognition_msgs::PointsArray>("output", 1);
00077     if (!jsk_topic_tools::readVectorParameter(*pnh_, "models", pcd_files)
00078         || pcd_files.size() == 0) {
00079       JSK_NODELET_FATAL("no models is specified");
00080       return;
00081     }
00082 
00083     for (size_t i = 0; i< pcd_files.size(); i++) {
00084       PointCloudData::Ptr data(new PointCloudData(pcd_files[i]));
00085       point_clouds_.push_back(data);
00086     }
00087     timer_ = pnh_->createTimer(ros::Duration(1.0),
00088                                boost::bind(
00089                                            &PointcloudDatabaseServer::timerCallback,
00090                                            this,
00091                                            _1));
00092   }
00093 
00094   void PointcloudDatabaseServer::timerCallback(const ros::TimerEvent& event)
00095   {
00096     jsk_recognition_msgs::PointsArray ros_out;
00097     ros_out.header.stamp = event.current_real;
00098     for (size_t i = 0; i < point_clouds_.size(); i++) {
00099       ros_out.cloud_list.push_back(point_clouds_[i]->getROSPointCloud(event.current_real));
00100                                                                       
00101     }
00102     pub_points_.publish(ros_out);
00103   }
00104 }
00105 
00106 #include <pluginlib/class_list_macros.h>
00107 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PointcloudDatabaseServer,
00108                         nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48