23 #ifndef __PLUGINS_ROBOTINO_IR_PCL_THREAD_H_
24 #define __PLUGINS_ROBOTINO_IR_PCL_THREAD_H_
26 #include <core/threading/thread.h>
27 #include <aspect/blocked_timing.h>
28 #include <aspect/logging.h>
29 #include <aspect/configurable.h>
30 #include <aspect/blackboard.h>
31 #include <aspect/pointcloud.h>
32 #include <pcl_utils/utils.h>
34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
39 class RobotinoSensorInterface;
57 protected:
virtual void run() { Thread::run(); }
65 float *angle_cosines_;
Thread aspect to access to BlackBoard.
virtual void run()
Stub to see name in backtrace for easier debugging.
RobotinoIrPclThread()
Constructor.
Thread aspect to provide and access point clouds.
Thread class encapsulation of pthreads.
RobotinoSensorInterface Fawkes BlackBoard Interface.
Thread aspect to use blocked timing.
Robotino IR distances as point cloud.
Thread aspect to log output.
virtual void finalize()
Finalize the thread.
virtual void loop()
Code to execute in the thread.
RefPtr<> is a reference-counting shared smartpointer.
virtual void init()
Initialize the thread.