Fawkes API  Fawkes Development Version
pcl_db_roscomm_thread.h
1 
2 /***************************************************************************
3  * pcl_db_roscomm_thread.h - ROS communication for pcl-db-merge
4  *
5  * Created: Thu Dec 06 13:52:27 2012
6  * Copyright 2012-2013 Tim Niemueller [www.niemueller.de]
7  ****************************************************************************/
8 
9 /* This program is free software; you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation; either version 2 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU Library General Public License for more details.
18  *
19  * Read the full text in the LICENSE.GPL file in the doc directory.
20  */
21 
22 #ifndef _PLUGINS_PERCEPTION_PCL_DB_ROS_PCL_DB_ROSCOMM_THREAD_H_
23 #define _PLUGINS_PERCEPTION_PCL_DB_ROS_PCL_DB_ROSCOMM_THREAD_H_
24 
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>
36 
37 namespace fawkes {
38 class PclDatabaseMergeInterface;
39 class PclDatabaseRetrieveInterface;
40 class PclDatabaseStoreInterface;
41 class BlackBoardOnUpdateWaker;
42 class WaitCondition;
43 } // namespace fawkes
44 namespace ros {
45 class ServiceServer;
46 }
47 
49  public fawkes::LoggingAspect,
53  public fawkes::ROSAspect,
55 {
56 public:
59 
60  virtual void init();
61  virtual void loop();
62  virtual void finalize();
63 
64 private:
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);
72 
73  /** Stub to see name in backtrace for easier debugging. @see Thread::run() */
74 protected:
75  virtual void
76  run()
77  {
78  Thread::run();
79  }
80 
81 private: // members
82  fawkes::PclDatabaseMergeInterface * merge_if_;
83  fawkes::PclDatabaseRetrieveInterface *retrieve_if_;
84  fawkes::PclDatabaseStoreInterface * store_if_;
85 
86  fawkes::BlackBoardOnUpdateWaker *merge_update_waker_;
87  fawkes::WaitCondition * merge_waitcond_;
88 
89  fawkes::BlackBoardOnUpdateWaker *retrieve_update_waker_;
90  fawkes::WaitCondition * retrieve_waitcond_;
91 
92  fawkes::BlackBoardOnUpdateWaker *store_update_waker_;
93  fawkes::WaitCondition * store_waitcond_;
94 
95  ros::ServiceServer *srv_merge_;
96  ros::ServiceServer *srv_retrieve_;
97  ros::ServiceServer *srv_store_;
98  ros::ServiceServer *srv_record_;
99 
100  unsigned int merge_msg_id_;
101  unsigned int retrieve_msg_id_;
102  unsigned int store_msg_id_;
103 
104  std::string cfg_store_pcl_id_;
105 };
106 
107 #endif
PointCloudDBROSCommThread::PointCloudDBROSCommThread
PointCloudDBROSCommThread()
Constructor.
Definition: pcl_db_roscomm_thread.cpp:46
PointCloudDBROSCommThread::init
virtual void init()
Initialize the thread.
Definition: pcl_db_roscomm_thread.cpp:58
PointCloudDBROSCommThread::loop
virtual void loop()
Code to execute in the thread.
Definition: pcl_db_roscomm_thread.cpp:118
fawkes::WaitCondition
Definition: wait_condition.h:42
PointCloudDBROSCommThread::run
virtual void run()
Stub to see name in backtrace for easier debugging.
Definition: pcl_db_roscomm_thread.h:76
fawkes::BlockedTimingAspect
Definition: blocked_timing.h:56
fawkes::BlackBoardOnUpdateWaker
Definition: on_update_waker.h:40
PointCloudDBROSCommThread::finalize
virtual void finalize()
Finalize the thread.
Definition: pcl_db_roscomm_thread.cpp:94
fawkes::BlackBoardAspect
Definition: blackboard.h:38
fawkes::PointCloudAspect
Definition: pointcloud.h:37
fawkes
fawkes::LoggingAspect
Definition: logging.h:38
fawkes::ROSAspect
Definition: ros.h:38
fawkes::Thread
Definition: thread.h:45
PointCloudDBROSCommThread::~PointCloudDBROSCommThread
virtual ~PointCloudDBROSCommThread()
Destructor.
Definition: pcl_db_roscomm_thread.cpp:53
fawkes::ConfigurableAspect
Definition: configurable.h:38
PointCloudDBROSCommThread
Definition: pcl_db_roscomm_thread.h:48