Fawkes API  Fawkes Development Version
pcl_frombuf_thread.h
1 
2 /***************************************************************************
3  * pointcloud_thread.h - OpenNI point cloud provider thread
4  *
5  * Created: Fri Mar 25 23:48:05 2011
6  * Copyright 2006-2011 Tim Niemueller [www.niemueller.de]
7  *
8  ****************************************************************************/
9 
10 /* This program is free software; you can redistribute it and/or modify
11  * it under the terms of the GNU General Public License as published by
12  * the Free Software Foundation; either version 2 of the License, or
13  * (at your option) any later version.
14  *
15  * This program is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18  * GNU Library General Public License for more details.
19  *
20  * Read the full text in the LICENSE.GPL file in the doc directory.
21  */
22 
23 #ifndef _PLUGINS_OPENNI_PCL_FROMBUF_THREAD_H_
24 #define _PLUGINS_OPENNI_PCL_FROMBUF_THREAD_H_
25 
26 // must be first for reliable ROS detection
27 #include <aspect/blocked_timing.h>
28 #include <aspect/clock.h>
29 #include <aspect/configurable.h>
30 #include <aspect/logging.h>
31 #include <aspect/pointcloud.h>
32 #include <core/threading/thread.h>
33 #include <core/utils/lockptr.h>
34 #include <fvutils/adapters/pcl.h>
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
37 #include <plugins/openni/aspect/openni.h>
38 #include <utils/time/time.h>
39 
40 #include <map>
41 
42 namespace firevision {
43 class SharedMemoryImageBuffer;
44 }
45 
48  public fawkes::LoggingAspect,
50  public fawkes::ClockAspect,
52 {
53 public:
55  virtual ~OpenNiPclOnlyThread();
56 
57  virtual void init();
58  virtual void loop();
59  virtual void finalize();
60 
61  /** Stub to see name in backtrace for easier debugging. @see Thread::run() */
62 protected:
63  virtual void
64  run()
65  {
66  Thread::run();
67  }
68 
69 private:
72 
73  fawkes::Time last_capture_time_;
74  unsigned int width_;
75  unsigned int height_;
76 };
77 
78 #endif
OpenNiPclOnlyThread::run
virtual void run()
Stub to see name in backtrace for easier debugging.
Definition: pcl_frombuf_thread.h:64
fawkes::RefPtr
RefPtr<> is a reference-counting shared smartpointer.
Definition: refptr.h:50
OpenNiPclOnlyThread::loop
virtual void loop()
Code to execute in the thread.
Definition: pcl_frombuf_thread.cpp:83
fawkes::BlockedTimingAspect
Thread aspect to use blocked timing.
Definition: blocked_timing.h:51
firevision::SharedMemoryImageBuffer
Shared memory image buffer.
Definition: shm_image.h:184
fawkes::PointCloudAspect
Thread aspect to provide and access point clouds.
Definition: pointcloud.h:38
fawkes::LoggingAspect
Thread aspect to log output.
Definition: logging.h:33
fawkes::Time
A class for handling time.
Definition: time.h:93
fawkes::Thread
Thread class encapsulation of pthreads.
Definition: thread.h:46
OpenNiPclOnlyThread::finalize
virtual void finalize()
Finalize the thread.
Definition: pcl_frombuf_thread.cpp:75
OpenNiPclOnlyThread::~OpenNiPclOnlyThread
virtual ~OpenNiPclOnlyThread()
Destructor.
Definition: pcl_frombuf_thread.cpp:52
fawkes::ConfigurableAspect
Thread aspect to access configuration data.
Definition: configurable.h:33
OpenNiPclOnlyThread::init
virtual void init()
Initialize the thread.
Definition: pcl_frombuf_thread.cpp:57
OpenNiPclOnlyThread::OpenNiPclOnlyThread
OpenNiPclOnlyThread()
Constructor.
Definition: pcl_frombuf_thread.cpp:45
fawkes::ClockAspect
Thread aspect that allows to obtain the current time from the clock.
Definition: clock.h:34
OpenNiPclOnlyThread
OpenNI Point Cloud Provider Thread.
Definition: pcl_frombuf_thread.h:52