fast_rcnn.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 import os.path as osp
6 import sys
7 
8 import itertools, pkg_resources
9 from distutils.version import LooseVersion
10 if LooseVersion(pkg_resources.get_distribution("chainer").version) >= LooseVersion('7.0.0') and \
11  sys.version_info.major == 2:
12  print('''Please install chainer < 7.0.0:
13 
14  sudo pip install chainer==6.7.0
15 
16 c.f https://github.com/jsk-ros-pkg/jsk_recognition/pull/2485
17 ''', file=sys.stderr)
18  sys.exit(1)
19 if [p for p in list(itertools.chain(*[pkg_resources.find_distributions(_) for _ in sys.path])) if "cupy-" in p.project_name] == []:
20  print('''Please install CuPy
21 
22  sudo pip install cupy-cuda[your cuda version]
23 i.e.
24  sudo pip install cupy-cuda91
25 
26 ''', file=sys.stderr)
27  # sys.exit(1)
28 import chainer
29 from chainer import cuda
30 import chainer.serializers as S
31 from chainer import Variable
32 import cv2
33 from distutils.version import LooseVersion
34 import numpy as np
35 
36 import cv_bridge
37 from dynamic_reconfigure.server import Server
38 from jsk_perception.cfg import FastRCNNConfig as Config
39 from jsk_recognition_msgs.msg import Rect, RectArray
40 from jsk_recognition_msgs.msg import ClassificationResult
41 import jsk_recognition_utils
42 from jsk_recognition_utils.chainermodels import VGG16FastRCNN
43 from jsk_recognition_utils.chainermodels import VGG_CNN_M_1024
44 from jsk_recognition_utils.nms import nms
45 from jsk_topic_tools import ConnectionBasedTransport
46 import message_filters
47 import rospkg
48 import rospy
49 from sensor_msgs.msg import Image
50 
51 
52 def img_preprocessing(orig_img, pixel_means, max_size=1000, scale=600):
53  img = orig_img.astype(np.float32, copy=True)
54  img -= pixel_means
55  im_size_min = np.min(img.shape[0:2])
56  im_size_max = np.max(img.shape[0:2])
57  im_scale = float(scale) / float(im_size_min)
58  if np.rint(im_scale * im_size_max) > max_size:
59  im_scale = float(max_size) / float(im_size_max)
60  img = cv2.resize(img, None, None, fx=im_scale, fy=im_scale,
61  interpolation=cv2.INTER_LINEAR)
62  return img.transpose([2, 0, 1]).astype(np.float32), im_scale
63 
64 
65 class FastRCNN(ConnectionBasedTransport):
66 
67  def __init__(self, model, target_names, pixel_means, use_gpu):
68  super(FastRCNN, self).__init__()
69 
70  self._srv = Server(Config, self.configCallback)
71 
72  self.model = model
73  self._pub_rects = self.advertise('~output/rect_array',
74  RectArray, queue_size=1)
75  self._pub_class = self.advertise('~output/class',
76  ClassificationResult, queue_size=1)
77  self.target_names = target_names
78  self.pixel_means = np.array(pixel_means, dtype=np.float32)
79  self.use_gpu = use_gpu
80  self.classifier_name = rospy.get_param("~classifier_name", rospy.get_name())
81 
82  def configCallback(self, config, level):
83  self.nms_thresh = config.nms_thresh
84  self.conf_thresh = config.conf_thresh
85  return config
86 
87  def subscribe(self):
88  self._sub = message_filters.Subscriber('~input', Image)
89  self._sub_rects = message_filters.Subscriber('~input/rect_array',
90  RectArray)
91  use_async = rospy.get_param('~approximate_sync', False)
92  queue_size = rospy.get_param('~queue_size', 100)
93  subs = [self._sub, self._sub_rects]
94  if use_async:
95  slop = rospy.get_param('~slop', 0.1)
96  sync = message_filters.ApproximateTimeSynchronizer(
97  subs, queue_size, slop)
98  else:
99  sync = message_filters.TimeSynchronizer(subs, queue_size)
100  sync.registerCallback(self._detect)
101 
102  def unsubscribe(self):
103  self._sub.unregister()
104  self._sub_rects.unregister()
105 
106  def _detect(self, imgmsg, rects_msg):
107  bridge = cv_bridge.CvBridge()
108  im_orig = bridge.imgmsg_to_cv2(imgmsg, desired_encoding='bgr8')
109  im, im_scale = img_preprocessing(im_orig, self.pixel_means)
110  rects_orig = jsk_recognition_utils.rects_msg_to_ndarray(rects_msg)
111  if len(rects_orig) == 0:
112  return
113  rects = rects_orig * im_scale
114  scores, bbox_pred = self._im_detect(im, rects)
115 
116  rects = RectArray(header=imgmsg.header)
117  labels = []
118  label_proba = []
119  for cls_id in range(1, len(self.target_names)):
120  _cls = scores[:, cls_id][:, np.newaxis]
121  _bbx = bbox_pred[:, cls_id * 4: (cls_id + 1) * 4]
122  dets = np.hstack((_bbx, _cls))
123  keep = nms(dets, self.nms_thresh)
124  dets = dets[keep, :]
125  orig_rects = cuda.cupy.asnumpy(rects_orig)[keep, :]
126 
127  inds = np.where(dets[:, -1] >= self.conf_thresh)[0]
128 
129  for i in inds:
130  _bbox = dets[i, :4]
131  x1, y1, x2, y2 = orig_rects[i]
132  width = x2 - x1
133  height = y2 - y1
134  center_x = x1 + 0.5 * width
135  center_y = y1 + 0.5 * height
136 
137  dx, dy, dw, dh = _bbox
138  _center_x = dx * width + center_x
139  _center_y = dy * height + center_y
140  _width = np.exp(dw) * width
141  _height = np.exp(dh) * height
142 
143  x1 = _center_x - 0.5 * _width
144  y1 = _center_y - 0.5 * _height
145  x2 = _center_x + 0.5 * _width
146  y2 = _center_y + 0.5 * _height
147  rect = Rect(x=x1, y=y1, width=x2-x1, height=y2-y1)
148  rects.rects.append(rect)
149  labels.append(cls_id)
150  label_proba.append(dets[:, -1][i])
151 
152  # publish classification result
153  clss = ClassificationResult(
154  header=imgmsg.header,
155  classifier=self.classifier_name,
156  target_names=self.target_names,
157  labels=labels,
158  label_names=[self.target_names[l] for l in labels],
159  label_proba=label_proba,
160  )
161  self._pub_rects.publish(rects)
162  self._pub_class.publish(clss)
163 
164  def _im_detect(self, im, rects):
165  xp = cuda.cupy if self.use_gpu else np
166  im = xp.asarray(im)
167  rects = xp.asarray(rects)
168  x_data = im[xp.newaxis, :, :, :]
169  # batch_indices is always 0 when batch size is 1
170  batch_indices = xp.zeros((len(rects), 1), dtype=np.float32)
171  rects = xp.hstack((batch_indices, rects))
172  if LooseVersion(chainer.__version__).version[0] < 2:
173  x = Variable(x_data, volatile=True)
174  rects_val = Variable(rects, volatile=True)
175  self.model.train = False
176  cls_score, bbox_pred = self.model(x, rects_val)
177  else:
178  with chainer.using_config('train', False), \
179  chainer.no_backprop_mode():
180  x = Variable(x_data)
181  rects_val = Variable(rects)
182  cls_score, bbox_pred = self.model(x, rects_val)
183 
184  scores = cuda.to_cpu(cls_score.data)
185  bbox_pred = cuda.to_cpu(bbox_pred.data)
186  return scores, bbox_pred
187 
188 
189 def main():
190  rospy.init_node('fast_rcnn_caffenet')
191 
192  # get parameters
193  try:
194  model_name = rospy.get_param('~model')
195  except KeyError as e:
196  rospy.logerr('Unspecified rosparam: {0}'.format(e))
197  sys.exit(1)
198 
199  gpu = rospy.get_param('~gpu', -1)
200  use_gpu = True if gpu >= 0 else False
201 
202  # setup model
203  PKG = 'jsk_perception'
204  rp = rospkg.RosPack()
205  data_path = osp.join(rp.get_path(PKG), 'trained_data')
206  if model_name == 'vgg_cnn_m_1024':
207  model = VGG_CNN_M_1024()
208  chainermodel = osp.join(data_path, 'vgg_cnn_m_1024.chainermodel')
209  elif model_name == 'vgg16':
210  model = VGG16FastRCNN()
211  chainermodel = osp.join(data_path, 'vgg16_fast_rcnn.chainermodel')
212  else:
213  rospy.logerr('Unsupported model: {0}'.format(model_name))
214  sys.exit(1)
215  rospy.loginfo('Loading chainermodel')
216  S.load_hdf5(chainermodel, model)
217  if use_gpu:
218  model.to_gpu(gpu)
219  rospy.loginfo('Finished loading chainermodel')
220 
221  # assumptions
222  target_names = [
223  '__background__',
224  'aeroplane',
225  'bicycle',
226  'bird',
227  'boat',
228  'bottle',
229  'bus',
230  'car',
231  'cat',
232  'chair',
233  'cow',
234  'diningtable',
235  'dog',
236  'horse',
237  'motorbike',
238  'person',
239  'pottedplant',
240  'sheep',
241  'sofa',
242  'train',
243  'tvmonitor',
244  ]
245  pixel_means = [102.9801, 115.9465, 122.7717]
246 
247  fast_rcnn = FastRCNN(
248  model=model, target_names=target_names,
249  pixel_means=pixel_means, use_gpu=use_gpu)
250  rospy.spin()
251 
252 
253 if __name__ == '__main__':
254  main()
def img_preprocessing(orig_img, pixel_means, max_size=1000, scale=600)
Definition: fast_rcnn.py:52
def _im_detect(self, im, rects)
Definition: fast_rcnn.py:164
def _detect(self, imgmsg, rects_msg)
Definition: fast_rcnn.py:106
def __init__(self, model, target_names, pixel_means, use_gpu)
Definition: fast_rcnn.py:67
def configCallback(self, config, level)
Definition: fast_rcnn.py:82


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