bof_histogram_extractor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 """
4 Extract BoF histogram in realtime.
5 """
6 
7 import gzip
8 import cPickle as pickle
9 from distutils.version import StrictVersion
10 from pkg_resources import get_distribution
11 
12 import numpy as np
13 from sklearn.preprocessing import normalize
14 
15 import cv_bridge
16 from jsk_recognition_msgs.msg import VectorArray
17 from jsk_recognition_utils import decompose_descriptors_with_label
18 from jsk_topic_tools import ConnectionBasedTransport
19 import message_filters
20 from posedetection_msgs.msg import Feature0D
21 from sensor_msgs.msg import Image
22 import rospy
23 
24 
25 class BoFHistogramExtractor(ConnectionBasedTransport):
26  def __init__(self):
27  super(BoFHistogramExtractor, self).__init__()
28 
29  self.queue_size = rospy.get_param('~queue_size', 10)
30 
31  # load bag of features
32  rospy.loginfo('Loading BoF data')
33  bof_data = rospy.get_param('~bof_data', None)
34  if bof_data is None:
35  quit()
36  with gzip.open(bof_data, 'rb') as f:
37  self.bof = pickle.load(f)
38  if (StrictVersion(get_distribution('scikit-learn').version) >=
39  StrictVersion('0.17.0')):
40  if 'n_jobs' not in self.bof.nn.__dict__:
41  # In scikit-learn>=0.17.0,
42  # sklearn.neighbors.NearestNeighbors needs 'n_jobs' attribute.
43  # https://github.com/jsk-ros-pkg/jsk_recognition/issues/1669
44  self.bof.nn.n_jobs = 1
45 
46  self._pub = self.advertise('~output', VectorArray, queue_size=1)
47  rospy.loginfo('Initialized BoF histogram extractor')
48 
49  def subscribe(self):
50  self._sub_feature = message_filters.Subscriber('~input', Feature0D)
51  self._sub_label = message_filters.Subscriber('~input/label', Image)
52  use_async = rospy.get_param('~approximate_sync', False)
53  if use_async:
54  slop = rospy.get_param('~slop', 0.1)
55  sync = message_filters.ApproximateTimeSynchronizer(
56  [self._sub_feature, self._sub_label],
57  queue_size=self.queue_size, slop=slop)
58  else:
60  [self._sub_feature, self._sub_label],
61  queue_size=self.queue_size)
62  rospy.logdebug('~approximate_sync: {}'.format(use_async))
63  sync.registerCallback(self._apply)
64 
65  def unsubscribe(self):
66  self._sub_feature.unregister()
67  self._sub_label.unregister()
68 
69  def _apply(self, feature_msg, label_msg):
70  bridge = cv_bridge.CvBridge()
71  label = bridge.imgmsg_to_cv2(label_msg)
72  desc = np.array(feature_msg.descriptors)
73  desc = desc.reshape((-1, feature_msg.descriptor_dim))
74  pos = np.array(feature_msg.positions)
75  pos = pos.reshape((-1, 2))
76  if label.sum() == 0:
77  rospy.logdebug('Skip image with only background label')
78  return
79  decomposed = decompose_descriptors_with_label(
80  descriptors=desc, positions=pos, label_img=label,
81  skip_zero_label=True)
82  X = np.array(decomposed.values())
83  if X.size == 0:
84  return
85  X = self.bof.transform(X)
86  normalize(X, copy=False)
87  self._pub.publish(
88  VectorArray(
89  header=feature_msg.header,
90  vector_dim=X.shape[1],
91  data=X.reshape(-1),
92  ))
93 
94 
95 if __name__ == '__main__':
96  rospy.init_node('bof_histogram_extractor')
97  extractor = BoFHistogramExtractor()
98  rospy.spin()


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27