22 #ifndef __PLUGINS_ROS_PCL_THREAD_H_
23 #define __PLUGINS_ROS_PCL_THREAD_H_
25 #include "pcl_adapter.h"
27 #include <core/threading/thread.h>
28 #include <aspect/blocked_timing.h>
29 #include <aspect/clock.h>
30 #include <aspect/configurable.h>
31 #include <aspect/logging.h>
32 #include <aspect/pointcloud.h>
33 #include <plugins/ros/aspect/ros.h>
34 #include <blackboard/interface_listener.h>
35 #include <blackboard/interface_observer.h>
36 #include <interfaces/TransformInterface.h>
37 #include <core/threading/mutex.h>
42 #include <ros/node_handle.h>
43 #include <sensor_msgs/PointCloud2.h>
63 protected:
virtual void run() { Thread::run(); }
71 sensor_msgs::PointCloud2 msg;
75 std::map<std::string, PublisherInfo> __pubs;
Thread aspect that allows to obtain the current time from the clock.
Thread aspect to get access to a ROS node handle.
virtual void run()
Stub to see name in backtrace for easier debugging.
RosPointCloudThread()
Constructor.
Thread aspect to provide and access point clouds.
virtual void loop()
Code to execute in the thread.
A class for handling time.
virtual ~RosPointCloudThread()
Destructor.
Thread class encapsulation of pthreads.
virtual void init()
Initialize the thread.
Thread aspect to use blocked timing.
Standalone PCL to ROS adapter class.
Thread aspect to log output.
virtual void finalize()
Finalize the thread.
Thread aspect to access configuration data.
Thread to exchange point clouds between Fawkes and ROS.