simple_lazy_transport.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib.message
4 import rospy
5 
6 from topic_tools import LazyTransport
7 
8 
10  def __init__(self):
11  super(self.__class__, self).__init__()
12  msg_name = rospy.get_param('~msg_name')
13  self.msg_class = roslib.message.get_message_class(msg_name)
14  self._pub = self.advertise('~output', self.msg_class, queue_size=1)
15 
16  def subscribe(self):
17  self._sub = rospy.Subscriber('~input', self.msg_class, self._process)
18 
19  def unsubscribe(self):
20  self._sub.unregister()
21 
22  def _process(self, img_msg):
23  self._pub.publish(img_msg)
24 
25 
26 if __name__ == '__main__':
27  rospy.init_node('simple_transport')
29  rospy.spin()
def advertise(self, args, kwargs)
Definition: __init__.py:70


topic_tools
Author(s): Morgan Quigley, Brian Gerkey
autogenerated on Sun Feb 3 2019 03:30:24