image_to_label.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import numpy as np
5 
6 import cv_bridge
7 from jsk_topic_tools import ConnectionBasedTransport
8 import rospy
9 from sensor_msgs.msg import Image
10 
11 
12 class ImageToLabel(ConnectionBasedTransport):
13  def __init__(self):
14  super(ImageToLabel, self).__init__()
15  self._pub = self.advertise('~output', Image, queue_size=1)
16 
17  def subscribe(self):
18  self._sub = rospy.Subscriber('~input', Image, self._convert)
19 
20  def unsubscribe(self):
21  self._sub.unregister()
22 
23  def _convert(self, msg):
24  bridge = cv_bridge.CvBridge()
25  img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
26  label = np.ones(img.shape[:2], dtype=np.int32)
27  label_msg = bridge.cv2_to_imgmsg(label, encoding='32SC1')
28  label_msg.header = msg.header
29  self._pub.publish(label_msg)
30 
31 
32 if __name__ == '__main__':
33  rospy.init_node('image_to_label')
34  img2label = ImageToLabel()
35  rospy.spin()


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