kittiseg.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 sys
34 import logging
35 import timeit
36 import tensorflow as tf
37 import rospy
38 from tools import ResizeAndCrop
39 
40 KITTISEG_ROOT_FOLDER = '/home/perfetto/KittiSeg_source' + '/incl/'
41 
42 sys.path.insert(1, KITTISEG_ROOT_FOLDER)
43 
44 try:
45  # Check whether setup was done correctly
46  import tensorvision.utils as tv_utils
47  import tensorvision.core as tv_core
48 
49 except ImportError:
50  # You forgot to initialize submodules
51  logging.error("Could not import the submodules.")
52 
53  import os
54  if not os.path.exists(KITTISEG_ROOT_FOLDER):
55  logging.error("KittiSeg folder " + KITTISEG_ROOT_FOLDER + ' in not found')
56  else:
57  logging.error("You use " + KITTISEG_ROOT_FOLDER + ' as KittSeg folder')
58 
59  import traceback
60  EX_TYPE, EX, TB = sys.exc_info()
61  traceback.print_tb(TB)
62 
63  exit(1)
64 
65 class KittiSegmenter(object):
66  """Class to initialize and run KittiSeg"""
67  def __init__(self, logdir, original_image_size, runCPU=False):
68  """Initialize KittiSeg:
69  Inputs: logdir (Directory to KittiSeg model),
70  runCPU (Optional, if set to True TensorFlow runs on CPU instead of GPU"""
71 
72  rospy.loginfo("Using weights found in {}".format(logdir))
73 
74  # Loading hyper-parameters from logdir
75  self.hypes = tv_utils.load_hypes_from_logdir(logdir, base_path='hypes')
76 
77  rospy.loginfo("self.hypes loaded successfully.")
78 
79  # Loading tv modules (encoder.py, decoder.py, eval.py) from logdir
80  modules = tv_utils.load_modules_from_logdir(logdir)
81  rospy.loginfo("Modules loaded successfully. Starting to build tf graph.")
82 
83  # Create tf graph and build module.
84  with tf.Graph().as_default():
85  tf_device = None
86  if runCPU:
87  tf_device = '/cpu:0'
88 
89  with tf.device(tf_device):
90  # Create placeholder for input
91  self.tf_image_pl = tf.placeholder(tf.float32)
92  tf_image = tf.expand_dims(self.tf_image_pl, 0)
93  tf_image.set_shape([1, None, None, 3])
94 
95  # build Tensorflow graph using the model from logdir
96  self.tf_prediction = tv_core.build_inference_graph(
97  self.hypes, modules, image=tf_image)
98 
99  rospy.loginfo("Graph build successfully.")
100 
101  # Create a session for running Ops on the Graph.
102 
103  # Config to turn on JIT compilation - 3 rows instead
104  # of simple tf_session = tf.Session()
105  #
106  # config = tf.ConfigProto()
107  # config.graph_options.optimizer_options.global_jit_level = tf.OptimizerOptions.ON_2
108  # tf_session = tf.Session(config=config)
109 
110  # tf_session=tf.ConfigProto(allow_soft_placement=True, log_device_placement=True))
111 
112  # gpu_options = tf.GPUOptions(per_process_gpu_memory_fraction=0.99)
113  # tf_session = tf.Session(config=tf.ConfigProto(gpu_options=gpu_options))
114 
115  self.tf_session = tf.Session()
116  tf_saver = tf.train.Saver()
117 
118  # Load weights from logdir
119  tv_core.load_weights(logdir, self.tf_session, tf_saver)
120 
121  rospy.loginfo("Weights loaded successfully.")
122 
123  self.tools = ResizeAndCrop(self.hypes, original_image_size)
125 
126  def run_processed_image(self, image):
127  """A function that runs an image through KittiSeg
128  Input: Image to process
129  Output: tagged_image, time_tf"""
130  feed = {self.tf_image_pl: image}
131  softmax = self.tf_prediction['softmax']
132 
133  time__tf_start = timeit.default_timer()
134  # ---------------------------------
135  output = self.tf_session.run([softmax], feed_dict=feed)
136  # ---------------------------------
137  time__tf = timeit.default_timer() - time__tf_start
138 
139  # Reshape output from flat vector to 2D Image
140  shape = image.shape
141  return output[0][:, 1].reshape(shape[0], shape[1]), time__tf
142 
143  def run_model_on_image(self, image):
144  """A function that sets up and runs an image through KittiSeg
145  Input: Image to process
146  Output: way_prediction, time_tf"""
147 
148  image_for_proc, self.output_image_uncropped = self.tools.preprocess_image(
149  image, self.output_image_uncropped)
150 
151  output_image, time_tf = self.run_processed_image(image_for_proc)
152 
153  # -----------------------------------------------------------------
154  # Plot confidences as red-blue overlay
155  # rb_image = seg.make_overlay(image, output_image)
156 
157  return self.tools.postprocess_image(
158  output_image, self.output_image_uncropped, image), time_tf
def __init__(self, logdir, original_image_size, runCPU=False)
Definition: kittiseg.py:67
def run_processed_image(self, image)
Definition: kittiseg.py:126
def run_model_on_image(self, image)
Definition: kittiseg.py:143


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