unwrap_histogram_with_range_array.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 """
00004 Convert HistogramWithRangeArray to HistogramWithRange
00005 """
00006 
00007 from jsk_topic_tools import ConnectionBasedTransport
00008 from jsk_recognition_msgs.msg import HistogramWithRange, HistogramWithRangeArray
00009 
00010 import rospy
00011 
00012 class HistogramWithRangeArrayUnwrapper(ConnectionBasedTransport):
00013     def __init__(self):
00014         super(HistogramWithRangeArrayUnwrapper, self).__init__()
00015         self._pub = self.advertise("~output", HistogramWithRange, queue_size=1)
00016     def subscribe(self):
00017         self._sub = rospy.Subscriber("~input", HistogramWithRangeArray, self.callback)
00018     def unsubscribe(self):
00019         self._sub.unregister()
00020     def callback(self, msg):
00021         if len(msg.histograms) > 0:
00022             self._pub.publish(msg.histograms[0])
00023 
00024 if __name__ == "__main__":
00025     rospy.init_node("unwrap_histogram_with_range_array")
00026     unwrapper = HistogramWithRangeArrayUnwrapper()
00027     rospy.spin()
00028     


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07