Fawkes API  Fawkes Development Version
gazsim_depthcam_thread.h
1 /***************************************************************************
2  * gazsim_depthcam_plugin.cpp - Plugin simulates a depthcam in Gazebo and
3  * provides a point cloud
4  *
5  * Created: Fri Feb 19 20:58:32 2016
6  * Copyright 2016 Frederik Zwilling
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_GAZSIM_DEPTHCAM_THREAD_H_
23 #define __PLUGINS_GAZSIM_DEPTHCAM_THREAD_H_
24 
25 #include <core/threading/thread.h>
26 #include <aspect/clock.h>
27 #include <aspect/configurable.h>
28 #include <aspect/logging.h>
29 #include <aspect/blackboard.h>
30 #include <aspect/blocked_timing.h>
31 #include <plugins/gazebo/aspect/gazebo.h>
32 #include <string.h>
33 
34 #include <aspect/pointcloud.h>
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
37 
38 
39 //from Gazebo
40 #include <gazebo/transport/TransportTypes.hh>
41 #include <gazebo/msgs/MessageTypes.hh>
42 #include <gazebo/transport/transport.hh>
43 
45 : public fawkes::Thread,
46  public fawkes::ClockAspect,
47  public fawkes::LoggingAspect,
51  public fawkes::GazeboAspect,
53 {
54  public:
56 
57  virtual void init();
58  virtual void loop();
59  virtual void finalize();
60 
61  private:
62  gazebo::transport::SubscriberPtr depthcam_sub_;
63 
64  //handler function for incoming depthcam data messages
65  void on_depthcam_data_msg(ConstPointCloudPtr &msg);
66 
67  //config values
68  //topic name of the gazebo message publisher
69  std::string topic_name_;
70  unsigned int width_;
71  unsigned int height_;
72  //id of the shared memory object
73  std::string shm_id_;
74  std::string frame_;
75  std::string pcl_id_;
76 
78 };
79 
80 #endif
Thread aspect to access to BlackBoard.
Definition: blackboard.h:34
Thread aspect that allows to obtain the current time from the clock.
Definition: clock.h:36
Thread simulates a number of depthcams in Gazebo.
Thread aspect to provide and access point clouds.
Definition: pointcloud.h:40
Thread aspect to get access to a Gazebo node handle.
Definition: gazebo.h:37
virtual void finalize()
Finalize the thread.
Thread class encapsulation of pthreads.
Definition: thread.h:42
Thread aspect to use blocked timing.
virtual void init()
Initialize the thread.
Thread aspect to log output.
Definition: logging.h:35
DepthcamSimThread()
Constructor.
Thread aspect to access configuration data.
Definition: configurable.h:35
RefPtr<> is a reference-counting shared smartpointer.
Definition: refptr.h:49
virtual void loop()
Code to execute in the thread.