3 from __future__
import absolute_import
4 from __future__
import division
5 from __future__
import print_function
8 import itertools, pkg_resources, sys
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: 14 sudo pip install chainer==6.7.0 16 c.f https://github.com/jsk-ros-pkg/jsk_recognition/pull/2485 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 22 sudo pip install cupy-cuda[your cuda version] 24 sudo pip install cupy-cuda91 29 from chainer
import cuda
30 import chainer.serializers
as S
31 from chainer
import Variable
32 from distutils.version
import LooseVersion
34 import skimage.transform
37 from jsk_recognition_msgs.msg
import ClassificationResult
40 from jsk_topic_tools
import ConnectionBasedTransport
42 import message_filters
44 from sensor_msgs.msg
import Image
49 mean_bgr = np.array([104.00698793, 116.66876762, 122.67891434])
52 super(self.__class__, self).
__init__()
54 self.
gpu = rospy.get_param(
'~gpu', -1)
59 elif self.
model_name ==
'vgg16_batch_normalization':
60 self.
model = VGG16BatchNormalization(
63 rospy.logerr(
'Unsupported ~model_name: {0}' 65 model_file = rospy.get_param(
'~model_file')
66 S.load_hdf5(model_file, self.
model)
68 self.model.to_gpu(self.
gpu)
69 self.
pub = self.advertise(
'~output', ClassificationResult,
72 '~debug/net_input', Image, queue_size=1)
75 if rospy.get_param(
'~use_mask',
False):
79 '~input', Image, queue_size=1, buff_size=2**24)
81 '~input/mask', Image, queue_size=1, buff_size=2**24)
82 self.
subs = [sub, sub_mask]
83 queue_size = rospy.get_param(
'~queue_size', 10)
84 if rospy.get_param(
'~approximate_sync',
False):
85 slop = rospy.get_param(
'~slop', 0.1)
86 sync = message_filters.ApproximateTimeSynchronizer(
87 self.
subs, queue_size=queue_size, slop=slop)
90 self.
subs, queue_size=queue_size)
93 sub = rospy.Subscriber(
94 '~input', Image, self.
_recognize, callback_args=
None,
95 queue_size=1, buff_size=2**24)
103 bridge = cv_bridge.CvBridge()
104 bgr = bridge.imgmsg_to_cv2(imgmsg, desired_encoding=
'bgr8')
105 if mask_msg
is not None:
106 mask = bridge.imgmsg_to_cv2(mask_msg)
107 if mask.shape != bgr.shape[:2]:
109 'Size of input image and mask is different')
112 logerr_throttle(10,
'Size of input mask is 0')
115 bgr = skimage.transform.resize(
117 input_msg = bridge.cv2_to_imgmsg(bgr.astype(np.uint8), encoding=
'bgr8')
118 input_msg.header = imgmsg.header
119 self.pub_input.publish(input_msg)
121 blob = (bgr - self.
mean_bgr).transpose((2, 0, 1))
122 x_data = np.array([blob], dtype=np.float32)
124 x_data = cuda.to_gpu(x_data, device=self.
gpu)
125 if LooseVersion(chainer.__version__) < LooseVersion(
'2.0.0'):
126 x = Variable(x_data, volatile=
True)
127 self.model.train =
False 130 with chainer.using_config(
'train',
False), \
131 chainer.no_backprop_mode():
135 proba = cuda.to_cpu(self.model.pred.data)[0]
136 label = np.argmax(proba)
138 label_proba = proba[label]
139 cls_msg = ClassificationResult(
140 header=imgmsg.header,
142 label_names=[label_name],
143 label_proba=[label_proba],
148 self.pub.publish(cls_msg)
151 if __name__ ==
'__main__':
152 rospy.init_node(
'vgg16_object_recognition')
def _recognize(self, imgmsg, mask_msg=None)