-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathtzc_topic.h
43 lines (32 loc) · 1.07 KB
/
tzc_topic.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
#ifndef __TZC_TOPIC_HPP__
#define __TZC_TOPIC_HPP__
#include "ros/ros.h"
#include "tzc_publisher.h"
#include "tzc_subscriber.h"
namespace tzc_transport
{
class Topic
{
public:
Topic(const ros::NodeHandle & parent) {
nh_ = parent;
}
~Topic() {
}
template < class M >
Publisher< M > advertise(const std::string & topic, uint32_t queue_size, uint32_t mem_size) {
ros::Publisher pub = nh_.advertise< M >(topic, queue_size);
return Publisher< M >(pub, topic, mem_size);
}
template < class M >
Subscriber< M > subscribe(const std::string & topic, uint32_t queue_size, void (*fp)(const boost::shared_ptr< const M > &),
const ros::TransportHints& hints = ros::TransportHints().tcpNoDelay()) {
SubscriberCallbackHelper< M > * phlp = new SubscriberCallbackHelper< M >(topic, fp);
ros::Subscriber sub = nh_.subscribe(topic, queue_size, &SubscriberCallbackHelper< M >::callback, phlp, hints);
return Subscriber< M >(sub, phlp);
}
private:
ros::NodeHandle nh_;
};
} // namespace tzc_transport
#endif // __TZC_TOPIC_HPP__