Fawkes API
Fawkes Development Version
Main Page
Related Pages
Modules
Namespaces
Classes
Files
File List
All
Classes
Namespaces
Functions
Variables
Typedefs
Enumerations
Enumerator
Friends
Groups
Pages
pcl_thread.h
1
2
/***************************************************************************
3
* pcl_thread.cpp - Thread to exchange point clouds
4
*
5
* Created: Mon Nov 07 02:26:35 2011
6
* Copyright 2011 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_ROS_PCL_THREAD_H_
23
#define __PLUGINS_ROS_PCL_THREAD_H_
24
25
#include "pcl_adapter.h"
26
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>
38
39
#include <list>
40
#include <queue>
41
42
#include <ros/node_handle.h>
43
#include <sensor_msgs/PointCloud2.h>
44
45
class
RosPointCloudThread
46
:
public
fawkes::Thread
,
47
public
fawkes::ClockAspect
,
48
public
fawkes::LoggingAspect
,
49
public
fawkes::ConfigurableAspect
,
50
public
fawkes::BlockedTimingAspect
,
51
public
fawkes::PointCloudAspect
,
52
public
fawkes::ROSAspect
53
{
54
public
:
55
RosPointCloudThread
();
56
virtual
~RosPointCloudThread
();
57
58
virtual
void
init
();
59
virtual
void
loop
();
60
virtual
void
finalize
();
61
62
/** Stub to see name in backtrace for easier debugging. @see Thread::run() */
63
protected
:
virtual
void
run
() { Thread::run(); }
64
65
private
:
66
RosPointCloudAdapter
*__adapter;
67
68
/// @cond INTERNALS
69
typedef
struct
{
70
ros::Publisher pub;
71
sensor_msgs::PointCloud2 msg;
72
fawkes::Time
last_sent;
73
} PublisherInfo;
74
/// @endcond
75
std::map<std::string, PublisherInfo> __pubs;
76
77
};
78
79
#endif
src
plugins
ros
pcl_thread.h
Generated by
1.8.3.1