pointcloud_database_server.h
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 
37 #ifndef JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_
38 #define JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <dynamic_reconfigure/server.h>
42 #include <sensor_msgs/PointCloud2.h>
43 #include <pcl/PolygonMesh.h>
44 #include <jsk_recognition_msgs/PointsArray.h>
45 #include "jsk_pcl_ros/PointcloudDatabaseServerConfig.h"
46 
47 namespace jsk_pcl_ros
48 {
49  class PointCloudData
50  {
51  public:
53  PointCloudData(const std::string fname);
54  virtual ~PointCloudData() { };
55  virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr
56  getPointCloud();
57  virtual sensor_msgs::PointCloud2
59 
60  protected:
61  const std::string file_name_;
62  std::string ext_;
63  pcl::PolygonMesh mesh_;
64  std::string stem_;
65  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
66  private:
67  };
68 
69  class PointcloudDatabaseServer: public pcl_ros::PCLNodelet
70  {
71  public:
72  virtual ~PointcloudDatabaseServer();
73  typedef jsk_pcl_ros::PointcloudDatabaseServerConfig Config;
74  protected:
75  virtual void onInit();
76  virtual void timerCallback(const ros::TimerEvent& event);
77  virtual void configCallback(Config &config, uint32_t level);
78  std::vector<std::string> files_;
79  // virtual void registerPointcloud();
80  // virtual void removePointcloud();
81  // virtual void listPointcloud();
87  std::vector<PointCloudData::Ptr> point_clouds_;
88  jsk_recognition_msgs::PointsArray array_msg_;
89  sensor_msgs::PointCloud2 point_msg_;
90 
91  double duration_;
92  bool use_array_;
93 
94  private:
95  };
96 }
97 
98 #endif
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
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
ros::Publisher
jsk_pcl_ros::PointCloudData::Ptr
boost::shared_ptr< PointCloudData > Ptr
Definition: pointcloud_database_server.h:116
pcl_ros::PCLNodelet
jsk_pcl_ros::PointcloudDatabaseServer::pub_cloud_
ros::Publisher pub_cloud_
Definition: pointcloud_database_server.h:117
boost::shared_ptr
jsk_pcl_ros::PointCloudData::~PointCloudData
virtual ~PointCloudData()
Definition: pointcloud_database_server.h:118
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
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
jsk_pcl_ros::PointCloudData::getPointCloud
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getPointCloud()
Definition: pointcloud_database_server_nodelet.cpp:97
jsk_pcl_ros::PointcloudDatabaseServer::Config
jsk_pcl_ros::PointcloudDatabaseServerConfig Config
Definition: pointcloud_database_server.h:105
pcl_nodelet.h
jsk_pcl_ros::PointCloudData::stem_
std::string stem_
Definition: pointcloud_database_server.h:128
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PointcloudDatabaseServer::timer_
ros::Timer timer_
Definition: pointcloud_database_server.h:118
jsk_pcl_ros::PointcloudDatabaseServer::point_clouds_
std::vector< PointCloudData::Ptr > point_clouds_
Definition: pointcloud_database_server.h:119
ros::TimerEvent
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
jsk_pcl_ros::PointCloudData::getROSPointCloud
virtual sensor_msgs::PointCloud2 getROSPointCloud(ros::Time stamp)
Definition: pointcloud_database_server_nodelet.cpp:103
ros::Time
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::PointcloudDatabaseServer::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: pointcloud_database_server_nodelet.cpp:156
ros::Timer
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


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