image_publisher.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 import os
00004 from threading import Lock
00005 
00006 import cv2
00007 import numpy as np
00008 
00009 import cv_bridge
00010 from cv_bridge.boost.cv_bridge_boost import getCvType
00011 import dynamic_reconfigure.server
00012 import rospy
00013 
00014 from jsk_perception.cfg import ImagePublisherConfig
00015 from sensor_msgs.msg import CameraInfo
00016 from sensor_msgs.msg import Image
00017 
00018 
00019 class ImagePublisher(object):
00020 
00021     def __init__(self):
00022         self.lock = Lock()
00023         self.imgmsg = None
00024         self.encoding = rospy.get_param('~encoding', 'bgr8')
00025         self.frame_id = rospy.get_param('~frame_id', 'camera')
00026         dynamic_reconfigure.server.Server(
00027             ImagePublisherConfig, self._cb_dyn_reconfig)
00028         self.pub = rospy.Publisher('~output', Image, queue_size=1)
00029         self.publish_info = rospy.get_param('~publish_info', True)
00030         if self.publish_info:
00031             self.pub_info = rospy.Publisher(
00032                 '~output/camera_info', CameraInfo, queue_size=1)
00033         rate = rospy.get_param('~rate', 1.)
00034         rospy.Timer(rospy.Duration(1. / rate), self.publish)
00035 
00036     def _cb_dyn_reconfig(self, config, level):
00037         file_name = config['file_name']
00038         config['file_name'] = os.path.abspath(file_name)
00039         img_bgr = cv2.imread(file_name)
00040         if img_bgr is None:
00041             rospy.logwarn('Could not read image file: {}'.format(file_name))
00042             with self.lock:
00043                 self.imgmsg = None
00044         else:
00045             rospy.loginfo('Read the image file: {}'.format(file_name))
00046             with self.lock:
00047                 self.imgmsg = self.cv2_to_imgmsg(img_bgr, self.encoding)
00048         return config
00049 
00050     def publish(self, event):
00051         if self.imgmsg is None:
00052             return
00053         now = rospy.Time.now()
00054         # setup ros message and publish
00055         with self.lock:
00056             self.imgmsg.header.stamp = now
00057             self.imgmsg.header.frame_id = self.frame_id
00058         self.pub.publish(self.imgmsg)
00059         if self.publish_info:
00060             info = CameraInfo()
00061             info.header.stamp = now
00062             info.header.frame_id = self.frame_id
00063             info.width = self.imgmsg.width
00064             info.height = self.imgmsg.height
00065             self.pub_info.publish(info)
00066 
00067     def cv2_to_imgmsg(self, img_bgr, encoding):
00068         bridge = cv_bridge.CvBridge()
00069         # resolve encoding
00070         if getCvType(encoding) == 0:
00071             # mono8
00072             img = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2GRAY)
00073         elif getCvType(encoding) == 2:
00074             # 16UC1
00075             img = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2GRAY)
00076             img = img.astype(np.float32)
00077             img = img / 255 * (2 ** 16)
00078             img = img.astype(np.uint16)
00079         elif getCvType(encoding) == 5:
00080             # 32FC1
00081             img = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2GRAY)
00082             img = img.astype(np.float32)
00083             img /= 255
00084         elif getCvType(encoding) == 16:
00085             # 8UC3
00086             if encoding in ('rgb8', 'rgb16'):
00087                 # RGB
00088                 img = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2RGB)
00089             else:
00090                 img = img_bgr
00091         else:
00092             rospy.logerr('unsupported encoding: {0}'.format(encoding))
00093             return
00094         return bridge.cv2_to_imgmsg(img, encoding=encoding)
00095 
00096 
00097 if __name__ == '__main__':
00098     rospy.init_node('image_publisher')
00099     ImagePublisher()
00100     rospy.spin()


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Sun Oct 8 2017 02:43:23