Go to the documentation of this file.00001
00002
00003
00004 import numpy as np
00005
00006 from jsk_topic_tools import ConnectionBasedTransport
00007 import rospy
00008 from sensor_msgs.msg import Image
00009 import cv_bridge
00010
00011
00012 class MaskImageToLabel(ConnectionBasedTransport):
00013 def __init__(self):
00014 super(MaskImageToLabel, self).__init__()
00015 self._pub = self.advertise('~output', Image, queue_size=1)
00016
00017 def subscribe(self):
00018 self._sub = rospy.Subscriber('~input', Image, self._apply)
00019
00020 def unsubscribe(self):
00021 self._sub.unregister()
00022
00023 def _apply(self, msg):
00024 bridge = cv_bridge.CvBridge()
00025 mask = bridge.imgmsg_to_cv2(msg, desired_encoding='mono8')
00026 if mask.size == 0:
00027 rospy.logdebug('Skipping empty image')
00028 return
00029 label = np.zeros(mask.shape, dtype=np.int32)
00030 label[mask == 0] = 0
00031 label[mask == 255] = 1
00032 label_msg = bridge.cv2_to_imgmsg(label, encoding='32SC1')
00033 label_msg.header = msg.header
00034 self._pub.publish(label_msg)
00035
00036
00037 if __name__ == '__main__':
00038 rospy.init_node('mask_image_to_label')
00039 mask2label = MaskImageToLabel()
00040 rospy.spin()