image_to_label.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 import numpy as np
00005 
00006 import cv_bridge
00007 from jsk_topic_tools import ConnectionBasedTransport
00008 import rospy
00009 from sensor_msgs.msg import Image
00010 
00011 
00012 class ImageToLabel(ConnectionBasedTransport):
00013     def __init__(self):
00014         super(ImageToLabel, 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._convert)
00019 
00020     def unsubscribe(self):
00021         self._sub.unregister()
00022 
00023     def _convert(self, msg):
00024         bridge = cv_bridge.CvBridge()
00025         img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
00026         label = np.ones(img.shape[:2], dtype=np.int32)
00027         label_msg = bridge.cv2_to_imgmsg(label, encoding='32SC1')
00028         label_msg.header = msg.header
00029         self._pub.publish(label_msg)
00030 
00031 
00032 if __name__ == '__main__':
00033     rospy.init_node('image_to_label')
00034     img2label = ImageToLabel()
00035     rospy.spin()


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07