7 import dynamic_reconfigure.server
 
    8 from jsk_recognition_msgs.msg 
import ClassificationResult
 
    9 from jsk_recognition_msgs.msg 
import RectArray
 
   12 from jsk_topic_tools 
import ConnectionBasedTransport
 
   13 from jsk_topic_tools 
import warn_no_remap
 
   14 import message_filters
 
   17 import sensor_msgs.msg
 
   19 from jsk_perception.cfg 
import DrawRectsConfig
 
   28             labelcolormap() * 255, 0, 255), dtype=np.uint8)
 
   31             'use_classification_result'])
 
   32         self.
approximate_sync = rospy.get_param(
'~approximate_sync', DrawRectsConfig.defaults[
'approximate_sync'])
 
   33         self.
queue_size = rospy.get_param(
'~queue_size', DrawRectsConfig.defaults[
'queue_size'])
 
   44         self.
buff_size = rospy.get_param(
'~buff_size', 640 * 480 * 3 // 5 * 70)
 
   45         rospy.loginfo(
"rospy.Subscriber buffer size : {}".format(self.
buff_size))
 
   54                 '{}/compressed'.format(rospy.resolve_name(
'~output')), sensor_msgs.msg.CompressedImage, queue_size=1)
 
   57                 '~output', sensor_msgs.msg.Image, queue_size=1)
 
   60         need_resubscribe = 
False 
   64             need_resubscribe = 
True 
   74             rospy.logwarn(
'Not valid font_path: {}'.format(self.
font_path))
 
   83         if need_resubscribe 
and self.is_subscribed():
 
   94         warn_no_remap(
'~input', 
'~input/rects')
 
   96         subs = [sub_image, sub_rects]
 
   99                 '~input/class', ClassificationResult)
 
  100             subs.append(sub_class)
 
  103             slop = rospy.get_param(
'~slop', 1.0)
 
  104             self.
sync = message_filters.ApproximateTimeSynchronizer(
 
  114         rospy.loginfo(
"  queue_size : {}".format(self.
queue_size))
 
  117         for sub 
in self.
subs:
 
  121         start_time = rospy.Time.now()
 
  124             np_arr = np.fromstring(img_msg.data, np.uint8)
 
  125             cv_img = cv2.imdecode(np_arr, cv2.IMREAD_COLOR)
 
  126             if img_msg.format.find(
"compressed rgb") > -1:
 
  127                 cv_img = cv_img[:, :, ::-1]
 
  129             cv_img = self.
bridge.imgmsg_to_cv2(img_msg, desired_encoding=
'bgr8')
 
  131         img = cv2.resize(cv_img, 
None,
 
  135         for i, rect 
in enumerate(rects_msg.rects):
 
  137                 label_idx = class_msg.labels[i]
 
  147             cv2.rectangle(img, pt1=pt1, pt2=pt2,
 
  148                           color=color.tolist(),
 
  150                           lineType=cv2.LINE_AA)
 
  152                 text = class_msg.label_names[i]
 
  153                 if self.
show_proba and len(class_msg.label_proba) > i:
 
  154                     text += 
' ({0:.2f})'.format(class_msg.label_proba[i])
 
  159                     img = put_text_to_image(
 
  162                         color=(255, 255, 255),
 
  163                         background_color=tuple(color),
 
  166                     pt1=(
int(pos_x), 
int(pos_y - 16))
 
  168                     cv2.rectangle(img, pt1, pt2,
 
  170                     cv2.putText(img, text, (pos_x, pos_y - 4),
 
  171                                 cv2.FONT_HERSHEY_PLAIN,
 
  172                                 fontScale=1, color=(255, 255, 255),
 
  173                                 thickness=1, lineType=cv2.LINE_AA)
 
  175             viz_msg = sensor_msgs.msg.CompressedImage()
 
  176             viz_msg.format = 
"jpeg" 
  177             viz_msg.data = np.array(cv2.imencode(
'.jpg', img)[1]).tostring()
 
  179             viz_msg = self.
bridge.cv2_to_imgmsg(img, encoding=
'bgr8')
 
  180         viz_msg.header = img_msg.header
 
  183         rospy.loginfo(
"processing time {} on message taken at {} sec ago".format(
 
  184             (rospy.Time.now() - start_time).to_sec(),
 
  185             (rospy.Time.now() - img_msg.header.stamp).to_sec()))
 
  188 if __name__ == 
'__main__':
 
  189     rospy.init_node(
'draw_rects')