Go to the documentation of this file.00001
00002
00003 from __future__ import absolute_import
00004 from __future__ import division
00005 from __future__ import print_function
00006
00007 import numpy as np
00008
00009 import cv_bridge
00010 from jsk_topic_tools import ConnectionBasedTransport
00011 import rospy
00012 from sensor_msgs.msg import Image
00013
00014
00015 class Image16UC1To32FC1(ConnectionBasedTransport):
00016
00017 def __init__(self):
00018 super(self.__class__, self).__init__()
00019 self.pub = self.advertise('~output', Image, queue_size=1)
00020
00021 def subscribe(self):
00022 self.sub = rospy.Subscriber('~input', Image, self.transport)
00023
00024 def unsubscribe(self):
00025 self.sub.unregister()
00026
00027 def transport(self, msg):
00028 if msg.height * msg.width == 0:
00029 return
00030 bridge = cv_bridge.CvBridge()
00031 img_16uc1 = bridge.imgmsg_to_cv2(msg, desired_encoding='16UC1')
00032 img_32fc1 = (img_16uc1.astype(np.float64) / (2**16)).astype(np.float32)
00033 out_msg = bridge.cv2_to_imgmsg(img_32fc1, '32FC1')
00034 out_msg.header = msg.header
00035 self.pub.publish(out_msg)
00036
00037
00038 if __name__ == '__main__':
00039 rospy.init_node('image_16uc1_to_32fc1')
00040 Image16UC1To32FC1()
00041 rospy.spin()