cnn_manager.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 # BSD 3-Clause License
3 
4 # Copyright (c) 2019, Noam C. Golombek
5 # All rights reserved.
6 
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions are met:
9 
10 # 1. Redistributions of source code must retain the above copyright notice, this
11 # list of conditions and the following disclaimer.
12 
13 # 2. Redistributions in binary form must reproduce the above copyright notice,
14 # this list of conditions and the following disclaimer in the documentation
15 # and/or other materials provided with the distribution.
16 
17 # 3. Neither the name of the copyright holder nor the names of its
18 # contributors may be used to endorse or promote products derived from
19 # this software without specific prior written permission.
20 
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31 
32 
33 import os
34 import logging
35 import timeit
36 import atexit
37 import numpy as np
38 import cv2
39 import rospy
40 
41 # TODO: Functions to support video save (get_from_video_out_video_name, video_out_grid )
42 # are not defined
43 
44 try:
45 
46  from tools import ImageSubscriber, StatisticsEngine, DrawingTools, Camera, VideoSaver, exit_handler, str2bool
47 
48 except ImportError:
49  # You forgot to initialize submodules
50  rospy.logfatal("Could not import the submodules.")
51 
52  import traceback
53  import sys
54  ex_type, ex, tb = sys.exc_info()
55  traceback.print_tb(tb)
56 
57  sys.exit(1)
58 
59 
60 class CNNManager(object):
61  def __init__(self, source, video_save, logdir, cpu, display, tensor_io, mode, gpu_percent=1):
62  self.statistics_engine = StatisticsEngine()
63 
64  self.mode = mode
65  # setup video output
66  self.DO_VIDEO_SAVE = str2bool(video_save, return_string=True)
67  assert not self.DO_VIDEO_SAVE # TODO: Functions to support are not implented
68 
69  self.camera = Camera(source)
70  tmp_image, tmp_frame = self.camera.get_image()
71 
72  if self.DO_VIDEO_SAVE:
73  video_name = self.DO_VIDEO_SAVE
74  if isinstance(video_name, bool):
75  video_name = self.camera.get_from_camera_video_name()
76 
77  if not video_name: # Means we get empty from camera, means we are in video
78  video_name = get_from_video_out_video_name(args)
79 
80  self.h_video_out = VideoSaver(
81  tmp_image, video_name=video_name)
82  self.h_video_out.print_info()
83 
84  self.DO_VIDEO_SAVE = True
85  rospy.loginfo(
86  'Video results of network run will be saved as %s', video_name)
87 
88  else:
89  rospy.loginfo('Video results of network run will not be saved')
90  self.h_video_out = None
91  self.DO_VIDEO_SAVE = False
92 
93  self.SHOW_DISPLAY = str2bool(display)
94 
95  if self.mode == 'segmentation':
96  from segmentation import MaskPublisher
97  from segmentation import DeepLabSegmenter as SegmentationProcessor
98  self.cnn_processor = SegmentationProcessor(logdir, self.camera.original_image_size, tensor_io, runCPU=cpu, gpu_percent=gpu_percent)
99 
100  elif self.mode == 'detection':
101  from detection import YoloDetector as YoloProcessor
102  from detection import DetectionPublisher
103  self.cnn_processor = YoloProcessor(logdir, self.camera.original_image_size, tensor_io, runCPU=cpu, gpu_percent=gpu_percent)
104 
105  self.statistics_engine.set_images_sizes(
106  self.camera.original_image_size, self.cnn_processor.tools.processing_image_size)
107 
108  atexit.register(exit_handler, self.camera,
109  self.h_video_out, self.statistics_engine)
110 
111  self.statistics_engine.set_time_end_of_start(timeit.default_timer())
112 
113  if self.mode == 'segmentation':
114  self.mask_publisher = MaskPublisher(
115  self.camera.original_image_size[0], self.camera.original_image_size[1])
116  self.drawing_tools = DrawingTools('segmentation')
117  elif self.mode == 'detection':
118  self.detection_publisher = DetectionPublisher()
119  self.drawing_tools = DrawingTools('detection')
120 
121  def run_loop(self):
122  count = 0
123 
124  while not rospy.is_shutdown():
125  # capture frames
126  time_iter_start = timeit.default_timer()
127 
128  image_frame, image_header = self.camera.get_image() # RGB
129 
130  if image_frame is None:
131  break
132 
133  # Open/Close video
134  if self.DO_VIDEO_SAVE is not False and count % video_out_grid == 0 and count > 0:
135  self.h_video_out.open_out_video(count=count)
136 
137  time_iter_start_inner = timeit.default_timer()
138 
139  # Run the network
140  cnn_result, time_pure_tf = self.cnn_processor.run_model_on_image(
141  image_frame)
142 
143  # send way_prediction mask
144  if self.mode == 'segmentation':
145  self.mask_publisher.send_mask(cnn_result, image_header)
146  elif self.mode == 'detection':
147  self.detection_publisher.send_mask(cnn_result, image_header)
148 
149 
150  time_iter_no_drawing = timeit.default_timer() - time_iter_start_inner
151 
152  # Plot the hard prediction as green overlay
153  if True or self.SHOW_DISPLAY or self.h_video_out is not None:
154  if self.mode == 'segmentation':
155  image_green = self.drawing_tools.overlay_segmentation(image_frame.copy(), cnn_result)
156  elif self.mode == 'detection':
157  image_green = self.drawing_tools.draw_detection(
158  image_frame.copy(), cnn_result['boxes'], cnn_result['scores'], cnn_result['classes'], [320,320])
159 
160 
161  time_iter_inner = timeit.default_timer() - time_iter_start_inner
162 
163  # Show images and save video
164  if self.SHOW_DISPLAY or self.h_video_out is not None:
165  frame_green = cv2.cvtColor(image_green, cv2.COLOR_RGB2BGR)
166  if self.SHOW_DISPLAY:
167  cv2.imshow('Path prediction', cv2.resize(
168  frame_green, dsize=self.camera.image_size_to_show))
169 
170  if self.h_video_out is not None:
171  assert self.h_video_out.h_video_out.isOpened()
172 
173  if self.camera.camera_type is "cv2vid":
174  self.h_video_out.h_video_out.write(frame_green)
175  else:
176  # the processing is done in RGB mode, but video writter expect (as part of cv2) images in BGR
177  self.h_video_out.h_video_out.write(
178  cv2.cvtColor(image_frame, cv2.COLOR_RGB2BGR))
179 
180  # record time
181  time_iter = timeit.default_timer() - time_iter_start
182 
183  str_to_print = '%d: Iteration spent %.4g inner %.4g' % (
184  count, time_iter, time_iter_inner)
185  if time_pure_tf is not None:
186  str_to_print += '\t(in tf was %.4g)' % time_pure_tf
187  self.statistics_engine.append_to_frame_times_tf(
188  time_pure_tf)
189 
190  rospy.logdebug(str_to_print)
191 
192  self.statistics_engine.append_to_frame_times_no_drawing(
193  time_iter_no_drawing)
194  self.statistics_engine.append_to_frame_times_inner(
195  time_iter_inner)
196  self.statistics_engine.append_to_frame_times_outer(time_iter)
197 
198  if count > 0:
199  self.statistics_engine.add_to_inner_time_spent(
200  time_iter_inner)
201  self.statistics_engine.add_to_overhead_spent(
202  time_iter - time_iter_inner)
203 
204  if time_pure_tf is not None:
205  self.statistics_engine.add_to_pure_tf_spent(
206  time_pure_tf)
207 
208  count += 1
209  self.statistics_engine.set_frame_count(count)
210 
211  # quit option - pres q to quit
212  if cv2.waitKey(1) & 0xFF == ord('q'):
213  break
214 
215  rospy.logfatal('CNN stopped!')
216  rospy.signal_shutdown('Segmentation closed. Shutting down...')
def str2bool(s, return_string=False)
Definition: misc.py:56
def __init__(self, source, video_save, logdir, cpu, display, tensor_io, mode, gpu_percent=1)
Definition: cnn_manager.py:61


cnn_bridge
Author(s): Noam C. Golombek , Alexander Beringolts
autogenerated on Mon Jun 10 2019 12:53:26