pointcloud_database_server.h
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 
00037 #ifndef JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_
00038 #define JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_
00039 
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <dynamic_reconfigure/server.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <pcl/PolygonMesh.h>
00044 #include <jsk_recognition_msgs/PointsArray.h>
00045 #include "jsk_pcl_ros/PointcloudDatabaseServerConfig.h"
00046 
00047 namespace jsk_pcl_ros
00048 {
00049   class PointCloudData
00050   {
00051   public:
00052     typedef boost::shared_ptr<PointCloudData> Ptr;
00053     PointCloudData(const std::string fname);
00054     virtual ~PointCloudData() { };
00055     virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00056     getPointCloud();
00057     virtual sensor_msgs::PointCloud2 
00058     getROSPointCloud(ros::Time stamp);
00059 
00060   protected:
00061     const std::string file_name_;
00062     std::string ext_;
00063     pcl::PolygonMesh mesh_;
00064     std::string stem_;
00065     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
00066   private:
00067   };
00068 
00069   class PointcloudDatabaseServer: public pcl_ros::PCLNodelet
00070   {
00071   public:
00072     virtual ~PointcloudDatabaseServer();
00073     typedef jsk_pcl_ros::PointcloudDatabaseServerConfig Config;
00074   protected:
00075     virtual void onInit();
00076     virtual void timerCallback(const ros::TimerEvent& event);
00077     virtual void configCallback(Config &config, uint32_t level);
00078     std::vector<std::string> files_;
00079     // virtual void registerPointcloud();
00080     // virtual void removePointcloud();
00081     // virtual void listPointcloud();
00082     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00083     boost::mutex mutex_;
00084     ros::Publisher pub_points_array_;
00085     ros::Publisher pub_cloud_;
00086     ros::Timer timer_;
00087     std::vector<PointCloudData::Ptr> point_clouds_;
00088     jsk_recognition_msgs::PointsArray array_msg_;
00089     sensor_msgs::PointCloud2 point_msg_;
00090 
00091     double duration_;
00092     bool use_array_;
00093 
00094   private:
00095   };
00096 }
00097 
00098 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50