object_array_publisher.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import genpy
00005 from jsk_recognition_msgs.msg import Object
00006 from jsk_recognition_msgs.msg import ObjectArray
00007 
00008 
00009 class ObjectArrayPublisher(object):
00010 
00011     def __init__(self):
00012         objects = rospy.get_param('~objects')
00013         self.msg = ObjectArray()
00014         for obj in objects:
00015             obj_msg = Object()
00016             genpy.message.fill_message_args(obj_msg, obj)
00017             self.msg.objects.append(obj_msg)
00018 
00019         latch = rospy.get_param('~latch', False)
00020         self._pub = rospy.Publisher('~output', ObjectArray, queue_size=1,
00021                                     latch=True)
00022         self._timer = rospy.Timer(rospy.Duration(1), self._timer_cb,
00023                                   oneshot=latch)
00024 
00025     def _timer_cb(self, event):
00026         self.msg.header.stamp = event.current_real
00027         self._pub.publish(self.msg)
00028 
00029 
00030 if __name__ == '__main__':
00031     rospy.init_node('object_array_publisher')
00032     app = ObjectArrayPublisher()
00033     rospy.spin()


jsk_recognition_msgs
Author(s):
autogenerated on Sun Oct 8 2017 02:42:41