-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathtzc_subscriber.h
105 lines (79 loc) · 1.96 KB
/
tzc_subscriber.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
#ifndef __TZC_SUBSCRIBER_HPP__
#define __TZC_SUBSCRIBER_HPP__
#include "ros/ros.h"
#include "tzc_object.h"
namespace tzc_transport
{
class Topic;
template < class M >
class Subscriber;
template < class M >
class SubscriberCallbackHelper
{
typedef void (*Func)(const typename M::ConstPtr &);
public:
~SubscriberCallbackHelper() {
}
void callback(const typename M::Ptr & msg) {
if (!pobj_) {
// If subscriber runs first, it will not die due to these code.
ShmManager * pshm = new ShmManager(boost::interprocess::open_only, name_.c_str());
pobj_ = ShmObjectPtr(new ShmObject(pshm, name_));
}
ShmMessage * ptr = pobj_->convertHandle2Address(msg->handle_);
// if the magic number don't match, the message has been released by now
if (ptr->magic_ != msg->magic_)
return;
ptr->take();
msg->fillArray(msg->handle_, ptr);
// call user callback
fp_(msg);
}
private:
SubscriberCallbackHelper(const std::string &topic, Func fp)
: pobj_(), name_(topic), fp_(fp) {
// change '/' in topic to '_'
for (int i = 0; i < name_.length(); i++)
if (name_[i] == '/')
name_[i] = '_';
}
ShmObjectPtr pobj_;
std::string name_;
Func fp_;
friend class Topic;
};
template < class M >
class Subscriber
{
public:
Subscriber() {
}
~Subscriber() {
}
Subscriber(const Subscriber & s) {
*this = s;
}
Subscriber & operator = (const Subscriber & s) {
sub_ = s.sub_;
phlp_ = s.phlp_;
return *this;
}
void shutdown() {
sub_.shutdown();
}
std::string getTopic() const {
return sub_.getTopic();
}
uint32_t getNumPublishers() const {
return sub_.getNumPublishers();
}
private:
Subscriber(const ros::Subscriber & sub, SubscriberCallbackHelper< M > * phlp)
: sub_(sub), phlp_(phlp) {
}
ros::Subscriber sub_;
boost::shared_ptr< SubscriberCallbackHelper< M > > phlp_;
friend class Topic;
};
} // namespace tzc_transport
#endif // __TZC_SUBSCRIBER_HPP__