unwrap_histogram_with_range_array.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 """
4 Convert HistogramWithRangeArray to HistogramWithRange
5 """
6 
7 from jsk_topic_tools import ConnectionBasedTransport
8 from jsk_recognition_msgs.msg import HistogramWithRange, HistogramWithRangeArray
9 
10 import rospy
11 
12 class HistogramWithRangeArrayUnwrapper(ConnectionBasedTransport):
13  def __init__(self):
14  super(HistogramWithRangeArrayUnwrapper, self).__init__()
15  self.index = rospy.get_param('~index', 0)
16  self._pub = self.advertise("~output", HistogramWithRange, queue_size=1)
17  def subscribe(self):
18  self._sub = rospy.Subscriber("~input", HistogramWithRangeArray, self.callback)
19  def unsubscribe(self):
20  self._sub.unregister()
21  def callback(self, msg):
22  if len(msg.histograms) > self.index:
23  self._pub.publish(msg.histograms[self.index])
24 
25 if __name__ == "__main__":
26  rospy.init_node("unwrap_histogram_with_range_array")
28  rospy.spin()
29 
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper.__init__
def __init__(self)
Definition: unwrap_histogram_with_range_array.py:13
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper._sub
_sub
Definition: unwrap_histogram_with_range_array.py:18
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper.subscribe
def subscribe(self)
Definition: unwrap_histogram_with_range_array.py:17
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper
Definition: unwrap_histogram_with_range_array.py:12
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper.index
index
Definition: unwrap_histogram_with_range_array.py:15
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper.unsubscribe
def unsubscribe(self)
Definition: unwrap_histogram_with_range_array.py:19
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper.callback
def callback(self, msg)
Definition: unwrap_histogram_with_range_array.py:21
node_scripts.unwrap_histogram_with_range_array.HistogramWithRangeArrayUnwrapper._pub
_pub
Definition: unwrap_histogram_with_range_array.py:16


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17