00001
00002
00003
00004 import collections
00005 import sys
00006 import cv2
00007 import cv_bridge
00008 import jsk_recognition_utils
00009 from jsk_topic_tools import ConnectionBasedTransport
00010 import message_filters
00011 import rospy
00012 from sensor_msgs.msg import Image
00013 import pkg_resources
00014 from distutils.version import StrictVersion
00015 from threading import Lock
00016
00017
00018 def draw_text_box(img, text, font_scale=0.8, thickness=2,
00019 color=(0, 255, 0), fg_color=(0, 0, 0), loc='ltb'):
00020 font_face = cv2.FONT_HERSHEY_SIMPLEX
00021 size, baseline = cv2.getTextSize(text, font_face, font_scale, thickness)
00022
00023 H, W = img.shape[:2]
00024
00025 if loc == 'ltb':
00026
00027 pt1 = (0, 0)
00028 pt2 = (size[0], size[1] + baseline)
00029 pt3 = (0, size[1])
00030 elif loc == 'rba':
00031 pt1 = (W - size[0], H - size[1] - baseline)
00032 pt2 = (W, H)
00033 pt3 = (W - size[0], H - baseline)
00034 else:
00035 raise ValueError
00036 if color is not None:
00037 cv2.rectangle(img, pt1, pt2, color=color, thickness=-1)
00038 cv2.putText(img, text, pt3, font_face, font_scale, fg_color, thickness)
00039
00040
00041 class TileImages(ConnectionBasedTransport):
00042 def __init__(self):
00043 super(TileImages, self).__init__()
00044 self.lock = Lock()
00045 self.input_topics = rospy.get_param('~input_topics', [])
00046 if not self.input_topics:
00047 rospy.logerr('need to specify input_topics')
00048 sys.exit(1)
00049 self._shape = rospy.get_param('~shape', None)
00050 if self._shape:
00051 if not (isinstance(self._shape, collections.Sequence) and
00052 len(self._shape) == 2):
00053 rospy.logerr('~shape must be a list of 2 float values.')
00054 sys.exit(1)
00055 if (self._shape[0] * self._shape[1]) < len(self.input_topics):
00056 rospy.logerr('Tile size must be larger than # of input topics')
00057 sys.exit(1)
00058 self.cache_img = None
00059 self.draw_topic_name = rospy.get_param('~draw_topic_name', False)
00060 self.approximate_sync = rospy.get_param('~approximate_sync', True)
00061 self.no_sync = rospy.get_param('~no_sync', False)
00062 self.font_scale = rospy.get_param('~font_scale', 0.8)
00063 if (not self.no_sync and
00064 StrictVersion(pkg_resources.get_distribution('message_filters').version) < StrictVersion('1.11.4') and
00065 self.approximate_sync):
00066 rospy.logerr('hydro message_filters does not support approximate sync. Force to set ~approximate_sync=false')
00067 self.approximate_sync = False
00068 self.pub_img = self.advertise('~output', Image, queue_size=1)
00069
00070 def subscribe(self):
00071 self.sub_img_list = []
00072 if self.no_sync:
00073 self.input_imgs = {}
00074 self.sub_img_list = [rospy.Subscriber(topic, Image, self.simple_callback(topic), queue_size=1) for topic in self.input_topics]
00075 rospy.Timer(rospy.Duration(0.1), self.timer_callback)
00076 else:
00077 for i, input_topic in enumerate(self.input_topics):
00078 sub_img = message_filters.Subscriber(input_topic, Image)
00079 self.sub_img_list.append(sub_img)
00080 if self.approximate_sync:
00081 async = message_filters.ApproximateTimeSynchronizer(
00082 self.sub_img_list, queue_size=10, slop=1)
00083 async.registerCallback(self._apply)
00084 else:
00085 sync = message_filters.TimeSynchronizer(
00086 self.sub_img_list, queue_size=10)
00087 sync.registerCallback(self._apply)
00088 def unsubscribe(self):
00089 for sub in self.sub_img_list:
00090 sub.sub.unregister()
00091 def timer_callback(self, event):
00092 with self.lock:
00093 imgs = [self.input_imgs[topic] for topic in self.input_topics
00094 if topic in self.input_imgs]
00095 self._append_images(imgs)
00096 def simple_callback(self, target_topic):
00097 def callback(msg):
00098 with self.lock:
00099 bridge = cv_bridge.CvBridge()
00100 img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
00101 self.input_imgs[target_topic] = img
00102 if self.draw_topic_name:
00103 draw_text_box(img, rospy.resolve_name(target_topic),
00104 font_scale=self.font_scale)
00105 return callback
00106 def _append_images(self, imgs):
00107 if not imgs:
00108 return
00109
00110
00111 shape_xy = self._shape[::-1] if self._shape else None
00112 if self.cache_img is None:
00113 out_bgr = jsk_recognition_utils.get_tile_image(
00114 imgs, tile_shape=shape_xy)
00115 self.cache_img = out_bgr
00116 else:
00117 try:
00118 out_bgr = jsk_recognition_utils.get_tile_image(
00119 imgs, tile_shape=shape_xy, result_img=self.cache_img)
00120 except ValueError:
00121 out_bgr = jsk_recognition_utils.get_tile_image(
00122 imgs, tile_shape=shape_xy)
00123 self.cache_img = out_bgr
00124 bridge = cv_bridge.CvBridge()
00125 imgmsg = bridge.cv2_to_imgmsg(out_bgr, encoding='bgr8')
00126 self.pub_img.publish(imgmsg)
00127 def _apply(self, *msgs):
00128 bridge = cv_bridge.CvBridge()
00129 imgs = []
00130 for msg, topic in zip(msgs, self.input_topics):
00131 img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
00132 if self.draw_topic_name:
00133 draw_text_box(img, rospy.resolve_name(topic),
00134 font_scale=self.font_scale)
00135 imgs.append(img)
00136 self._append_images(imgs)
00137
00138
00139 if __name__ == '__main__':
00140 rospy.init_node('tile_image')
00141 tile_image = TileImages()
00142 rospy.spin()