22 #ifndef _PLUGINS_PERCEPTION_PCL_DB_ROS_PCL_DB_ROSCOMM_THREAD_H_
23 #define _PLUGINS_PERCEPTION_PCL_DB_ROS_PCL_DB_ROSCOMM_THREAD_H_
25 #include <aspect/blackboard.h>
26 #include <aspect/blocked_timing.h>
27 #include <aspect/configurable.h>
28 #include <aspect/logging.h>
29 #include <aspect/pointcloud.h>
30 #include <core/threading/thread.h>
31 #include <fawkes_msgs/MergePointClouds.h>
32 #include <fawkes_msgs/RecordData.h>
33 #include <fawkes_msgs/RetrievePointCloud.h>
34 #include <fawkes_msgs/StorePointCloud.h>
35 #include <plugins/ros/aspect/ros.h>
38 class PclDatabaseMergeInterface;
39 class PclDatabaseRetrieveInterface;
40 class PclDatabaseStoreInterface;
41 class BlackBoardOnUpdateWaker;
65 bool merge_cb(fawkes_msgs::MergePointClouds::Request & req,
66 fawkes_msgs::MergePointClouds::Response &resp);
67 bool retrieve_cb(fawkes_msgs::RetrievePointCloud::Request & req,
68 fawkes_msgs::RetrievePointCloud::Response &resp);
69 bool store_cb(fawkes_msgs::StorePointCloud::Request & req,
70 fawkes_msgs::StorePointCloud::Response &resp);
71 bool record_cb(fawkes_msgs::RecordData::Request &req, fawkes_msgs::RecordData::Response &resp);
82 fawkes::PclDatabaseMergeInterface * merge_if_;
83 fawkes::PclDatabaseRetrieveInterface *retrieve_if_;
84 fawkes::PclDatabaseStoreInterface * store_if_;
95 ros::ServiceServer *srv_merge_;
96 ros::ServiceServer *srv_retrieve_;
97 ros::ServiceServer *srv_store_;
98 ros::ServiceServer *srv_record_;
100 unsigned int merge_msg_id_;
101 unsigned int retrieve_msg_id_;
102 unsigned int store_msg_id_;
104 std::string cfg_store_pcl_id_;