metadata_service.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 # BSD 3-Clause License
3 # Copyright (c) 2019, Noam C. Golombek
4 # All rights reserved.
5 
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 
9 # 1. Redistributions of source code must retain the above copyright notice, this
10 # list of conditions and the following disclaimer.
11 
12 # 2. Redistributions in binary form must reproduce the above copyright notice,
13 # this list of conditions and the following disclaimer in the documentation
14 # and/or other materials provided with the distribution.
15 
16 # 3. Neither the name of the copyright holder nor the names of its
17 # contributors may be used to endorse or promote products derived from
18 # this software without specific prior written permission.
19 
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 import os
32 import json
33 import rospy
34 import unicodedata
35 
36 from std_msgs.msg import String, Int8, ColorRGBA
37 from cnn_bridge.srv import *
38 from cnn_bridge.msg import SegmentationClass
39 
40 
41 class MetadataService(object):
42  def __init__(self, shape, classPath, logdir, mode):
43  try:
44  classes_parsed = json.load(open(classPath, "r"))['classes']
45  if mode == "segmentation":
46  self.metadata = getSegmentationMetadataResponse()
47  self.metadata.class_metadata = []
48 
49  for current_class in classes_parsed:
50  class_msg = SegmentationClass()
51  class_msg.color = ColorRGBA()
52  class_msg.color.r = classes_parsed[current_class]['color'][0]
53  class_msg.color.g = classes_parsed[current_class]['color'][1]
54  class_msg.color.b = classes_parsed[current_class]['color'][2]
55  class_msg.classification = Int8(classes_parsed[current_class]['id'])
56  class_msg.classification_name = String(classes_parsed[current_class]['name'])
57  class_msg.parent_class = Int8(classes_parsed[current_class]['id_category'])
58  class_msg.parent_name = String(classes_parsed[current_class]['category'])
59  self.metadata.class_metadata.append(class_msg)
60 
61 
62  self.s = rospy.Service(rospy.get_name() + '/get_cnn_metadata',
63  getSegmentationMetadata, self.get_cnn_metadata_callback)
64  elif mode == "detection":
65  self.metadata = getDetectionMetadataResponse()
66  self.metadata.class_names = []
67  for current_class in classes_parsed:
68  self.metadata.class_names.append(String(unicodedata.normalize('NFKD', current_class).encode('ascii','ignore')))
69  self.s = rospy.Service(rospy.get_name() + '/get_cnn_metadata',
70  getDetectionMetadata, self.get_cnn_metadata_callback)
71 
72  except IOError as e:
73  rospy.logerr("Could not read metadata file\nI/O error({0}): {1}".format(e.errno, e.strerror))
74  self.metadata.image_height = shape[1]
75  self.metadata.image_width = shape[0]
76 
77 
78 
79  def get_cnn_metadata_callback(self, req):
80  rospy.logdebug("Sent metadata about node {0}".format(rospy.get_name()))
81  return self.metadata
def __init__(self, shape, classPath, logdir, mode)


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