tile_image.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import collections
5 import sys
6 import cv2
7 import cv_bridge
8 import jsk_recognition_utils
9 from jsk_topic_tools import ConnectionBasedTransport
10 import message_filters
11 import rospy
12 from sensor_msgs.msg import Image
13 import itertools, pkg_resources
14 from distutils.version import StrictVersion
15 from threading import Lock
16 
17 
18 def draw_text_box(img, text, font_scale=0.8, thickness=2,
19  color=(0, 255, 0), fg_color=(0, 0, 0), loc='ltb'):
20  font_face = cv2.FONT_HERSHEY_SIMPLEX
21  size, baseline = cv2.getTextSize(text, font_face, font_scale, thickness)
22 
23  H, W = img.shape[:2]
24 
25  if loc == 'ltb': # left + top + below
26  # pt: (x, y)
27  pt1 = (0, 0)
28  pt2 = (size[0], size[1] + baseline)
29  pt3 = (0, size[1])
30  elif loc == 'rba': # right + bottom + above
31  pt1 = (W - size[0], H - size[1] - baseline)
32  pt2 = (W, H)
33  pt3 = (W - size[0], H - baseline)
34  else:
35  raise ValueError
36  if color is not None:
37  cv2.rectangle(img, pt1, pt2, color=color, thickness=-1)
38  cv2.putText(img, text, pt3, font_face, font_scale, fg_color, thickness)
39 
40 
41 class TileImages(ConnectionBasedTransport):
42  def __init__(self):
43  super(TileImages, self).__init__()
44  self.lock = Lock()
45  self.input_topics = rospy.get_param('~input_topics', [])
46  if not self.input_topics:
47  rospy.logerr('need to specify input_topics')
48  sys.exit(1)
49  self._shape = rospy.get_param('~shape', None)
50  if self._shape:
51  if not (isinstance(self._shape, collections.Sequence) and
52  len(self._shape) == 2):
53  rospy.logerr('~shape must be a list of 2 float values.')
54  sys.exit(1)
55  if (self._shape[0] * self._shape[1]) < len(self.input_topics):
56  rospy.logerr('Tile size must be larger than # of input topics')
57  sys.exit(1)
58  self.cache_img = None
59  self.draw_topic_name = rospy.get_param('~draw_topic_name', False)
60  self.approximate_sync = rospy.get_param('~approximate_sync', True)
61  self.no_sync = rospy.get_param('~no_sync', False)
62  self.font_scale = rospy.get_param('~font_scale', 0.8)
63  if (not self.no_sync and
64  StrictVersion(pkg_resources.get_distribution('message_filters').version) < StrictVersion('1.11.4') and
65  self.approximate_sync):
66  rospy.logerr('hydro message_filters does not support approximate sync. Force to set ~approximate_sync=false')
67  self.approximate_sync = False
68  self.pub_img = self.advertise('~output', Image, queue_size=1)
69 
70  def subscribe(self):
71  self.sub_img_list = []
72  if self.no_sync:
73  self.input_imgs = {}
74  self.sub_img_list = [rospy.Subscriber(topic, Image, self.simple_callback(topic), queue_size=1) for topic in self.input_topics]
75  rospy.Timer(rospy.Duration(0.1), self.timer_callback)
76  else:
77  queue_size = rospy.get_param('~queue_size', 10)
78  slop = rospy.get_param('~slop', 1)
79  for i, input_topic in enumerate(self.input_topics):
80  sub_img = message_filters.Subscriber(input_topic, Image)
81  self.sub_img_list.append(sub_img)
82  if self.approximate_sync:
83  sync = message_filters.ApproximateTimeSynchronizer(
84  self.sub_img_list, queue_size=queue_size, slop=slop)
85  sync.registerCallback(self._apply)
86  else:
88  self.sub_img_list, queue_size=queue_size)
89  sync.registerCallback(self._apply)
90  def unsubscribe(self):
91  for sub in self.sub_img_list:
92  sub.sub.unregister()
93  def timer_callback(self, event):
94  with self.lock:
95  imgs = [self.input_imgs[topic] for topic in self.input_topics
96  if topic in self.input_imgs]
97  self._append_images(imgs)
98  def simple_callback(self, target_topic):
99  def callback(msg):
100  with self.lock:
101  bridge = cv_bridge.CvBridge()
102  img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
103  self.input_imgs[target_topic] = img
104  if self.draw_topic_name:
105  draw_text_box(img, rospy.resolve_name(target_topic),
106  font_scale=self.font_scale)
107  return callback
108  def _append_images(self, imgs):
109  if not imgs:
110  return
111  # convert tile shape: (Y, X) -> (X, Y)
112  # if None, shape is automatically decided to be square AMAP.
113  shape_xy = self._shape[::-1] if self._shape else None
114  if self.cache_img is None:
116  imgs, tile_shape=shape_xy)
117  self.cache_img = out_bgr
118  else:
119  try:
121  imgs, tile_shape=shape_xy, result_img=self.cache_img)
122  except ValueError: # cache miss
124  imgs, tile_shape=shape_xy)
125  self.cache_img = out_bgr
126  bridge = cv_bridge.CvBridge()
127  imgmsg = bridge.cv2_to_imgmsg(out_bgr, encoding='bgr8')
128  self.pub_img.publish(imgmsg)
129  def _apply(self, *msgs):
130  bridge = cv_bridge.CvBridge()
131  imgs = []
132  for msg, topic in zip(msgs, self.input_topics):
133  img = bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
134  if self.draw_topic_name:
135  draw_text_box(img, rospy.resolve_name(topic),
136  font_scale=self.font_scale)
137  imgs.append(img)
138  self._append_images(imgs)
139 
140 
141 if __name__ == '__main__':
142  rospy.init_node('tile_image')
143  tile_image = TileImages()
144  rospy.spin()
def simple_callback(self, target_topic)
Definition: tile_image.py:98
def draw_text_box(img, text, font_scale=0.8, thickness=2, color=(0, 255, 0), fg_color=(0, 0, 0), loc='ltb')
Definition: tile_image.py:19
void callback(const sensor_msgs::Image::ConstPtr &rgb_image, const sensor_msgs::Image::ConstPtr &depth_image, const sensor_msgs::CameraInfo::ConstPtr &rgb_camera_info, const sensor_msgs::CameraInfo::ConstPtr &depth_camera_info)
Definition: linemod.cpp:201


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