mask_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 from jsk_topic_tools import ConnectionBasedTransport
7 import rospy
8 from sensor_msgs.msg import Image
9 import cv_bridge
10 
11 
12 class MaskImageToLabel(ConnectionBasedTransport):
13  def __init__(self):
14  super(MaskImageToLabel, 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._apply)
19 
20  def unsubscribe(self):
21  self._sub.unregister()
22 
23  def _apply(self, msg):
24  bridge = cv_bridge.CvBridge()
25  mask = bridge.imgmsg_to_cv2(msg, desired_encoding='mono8')
26  if mask.size == 0:
27  rospy.logdebug('Skipping empty image')
28  return
29  label = np.zeros(mask.shape, dtype=np.int32)
30  label[mask == 0] = 0
31  label[mask == 255] = 1
32  label_msg = bridge.cv2_to_imgmsg(label, encoding='32SC1')
33  label_msg.header = msg.header
34  self._pub.publish(label_msg)
35 
36 
37 if __name__ == '__main__':
38  rospy.init_node('mask_image_to_label')
39  mask2label = MaskImageToLabel()
40  rospy.spin()
node_scripts.mask_image_to_label.MaskImageToLabel._apply
def _apply(self, msg)
Definition: mask_image_to_label.py:23
node_scripts.mask_image_to_label.MaskImageToLabel.unsubscribe
def unsubscribe(self)
Definition: mask_image_to_label.py:20
node_scripts.mask_image_to_label.MaskImageToLabel._pub
_pub
Definition: mask_image_to_label.py:15
node_scripts.mask_image_to_label.MaskImageToLabel
Definition: mask_image_to_label.py:12
node_scripts.mask_image_to_label.MaskImageToLabel.subscribe
def subscribe(self)
Definition: mask_image_to_label.py:17
node_scripts.mask_image_to_label.MaskImageToLabel._sub
_sub
Definition: mask_image_to_label.py:18
node_scripts.mask_image_to_label.MaskImageToLabel.__init__
def __init__(self)
Definition: mask_image_to_label.py:13


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17