5 from __future__
import absolute_import
6 from __future__
import division
7 from __future__
import print_function
10 from chainer
import cuda
11 import chainer.serializers
as S
12 from chainer
import Variable
13 from distutils.version
import LooseVersion
15 import skimage.transform
18 from jsk_recognition_msgs.msg
import ClassificationResult
21 from jsk_topic_tools
import ConnectionBasedTransport
25 from sensor_msgs.msg
import Image
27 from train
import PreprocessedDataset
32 Classify spectrogram using neural network
33 input: sensor_msgs/Image, 8UC1
34 output jsk_recognition_msgs/ClassificationResult
38 super(self.__class__, self).
__init__()
39 self.
gpu = rospy.get_param(
'~gpu', -1)
44 if not name.endswith(
'\n'):
53 n_class=len(self.target))
55 rospy.logerr(
'Unsupported ~model_name: {0}'
57 model_file = rospy.get_param(
59 osp.join(self.
dataset.root,
'result',
61 S.load_npz(model_file, self.
model)
64 self.
pub = self.advertise(
'~output', ClassificationResult,
67 '~debug/net_input', Image, queue_size=1)
70 sub = rospy.Subscriber(
71 '~input', Image, self.
_recognize, callback_args=
None,
72 queue_size=1, buff_size=2**24)
80 bridge = cv_bridge.CvBridge()
81 mono = bridge.imgmsg_to_cv2(imgmsg)
83 bgr = skimage.transform.resize(
85 input_msg = bridge.cv2_to_imgmsg(bgr.astype(np.uint8), encoding=
'bgr8')
86 input_msg.header = imgmsg.header
96 rgb = bgr.transpose((2, 0, 1))[::-1, :, :]
97 rgb = self.
dataset.process_image(rgb)
98 x_data = np.array([rgb], dtype=np.float32)
100 x_data = cuda.to_gpu(x_data, device=self.
gpu)
101 if LooseVersion(chainer.__version__) < LooseVersion(
'2.0.0'):
102 x = Variable(x_data, volatile=
True)
103 self.
model.train =
False
106 with chainer.using_config(
'train',
False), \
107 chainer.no_backprop_mode():
114 for i
in range(len(swap_labels)):
115 if not (i
in swap_labels):
116 rospy.logerr(
'Wrong target_names is given by rosparam.')
118 proba = cuda.to_cpu(self.
model.pred.data)[0]
119 proba_swapped = [proba[swap_labels[i]]
for i, p
in enumerate(proba)]
120 label_swapped = np.argmax(proba_swapped)
122 label_proba = proba_swapped[label_swapped]
123 cls_msg = ClassificationResult(
124 header=imgmsg.header,
125 labels=[label_swapped],
126 label_names=[label_name],
127 label_proba=[label_proba],
128 probabilities=proba_swapped,
132 self.
pub.publish(cls_msg)
135 if __name__ ==
'__main__':
136 rospy.init_node(
'sound_classifier')