alexnet_object_recognition.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import absolute_import
4 from __future__ import division
5 from __future__ import print_function
6 
7 import itertools, pkg_resources, sys
8 from distutils.version import LooseVersion
9 if LooseVersion(pkg_resources.get_distribution("chainer").version) >= LooseVersion('7.0.0') and \
10  sys.version_info.major == 2:
11  print('''Please install chainer < 7.0.0:
12 
13  sudo pip install chainer==6.7.0
14 
15 c.f https://github.com/jsk-ros-pkg/jsk_recognition/pull/2485
16 ''', file=sys.stderr)
17  sys.exit(1)
18 if [p for p in list(itertools.chain(*[pkg_resources.find_distributions(_) for _ in sys.path])) if "cupy-" in p.project_name ] == []:
19  print('''Please install CuPy
20 
21  sudo pip install cupy-cuda[your cuda version]
22 i.e.
23  sudo pip install cupy-cuda91
24 
25 ''', file=sys.stderr)
26  # sys.exit(1)
27 import chainer.serializers as S
28 from jsk_recognition_msgs.msg import ClassificationResult
29 from jsk_recognition_utils.chainermodels import AlexNet
30 from jsk_recognition_utils.chainermodels import AlexNetBatchNormalization
31 import rospy
32 from sensor_msgs.msg import Image
33 from vgg16_object_recognition import VGG16ObjectRecognition
34 
35 
36 class AlexNetObjectRecognition(VGG16ObjectRecognition):
37 
38  def __init__(self):
39  super(VGG16ObjectRecognition, self).__init__()
40  self.insize = 227
41  self.gpu = rospy.get_param('~gpu', -1)
42  self.target_names = rospy.get_param('~target_names')
43  self.model_name = rospy.get_param('~model_name')
44  if self.model_name == 'alexnet':
45  self.model = AlexNet(n_class=len(self.target_names))
46  elif self.model_name == 'alexnet_batch_normalization':
47  self.model = AlexNetBatchNormalization(
48  n_class=len(self.target_names))
49  else:
50  rospy.logerr('Unsupported ~model_name: {0}'
51  .format(self.model_name))
52  model_file = rospy.get_param('~model_file')
53  S.load_hdf5(model_file, self.model)
54  if self.gpu != -1:
55  self.model.to_gpu(self.gpu)
56  self.pub = self.advertise('~output', ClassificationResult,
57  queue_size=1)
58  self.pub_input = self.advertise(
59  '~debug/net_input', Image, queue_size=1)
60 
61 
62 if __name__ == '__main__':
63  rospy.init_node('alexnet_object_recognition')
65  rospy.spin()


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