00001 """autogenerated by genpy from mod_semantic_map/GenerateSemanticMapOWLRequest.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import mod_semantic_map.msg
00008 import std_msgs.msg
00009
00010 class GenerateSemanticMapOWLRequest(genpy.Message):
00011 _md5sum = "f60c6df582433e7b1f63324006360c40"
00012 _type = "mod_semantic_map/GenerateSemanticMapOWLRequest"
00013 _has_header = False
00014 _full_text = """SemMap map
00015
00016 ================================================================================
00017 MSG: mod_semantic_map/SemMap
00018 # Semantic map message type, Moritz Tenorth, tenorth@cs.tum.edu
00019 Header header # Message header
00020 SemMapObject[] objects # List of objects in the map
00021
00022 ================================================================================
00023 MSG: std_msgs/Header
00024 # Standard metadata for higher-level stamped data types.
00025 # This is generally used to communicate timestamped data
00026 # in a particular coordinate frame.
00027 #
00028 # sequence ID: consecutively increasing ID
00029 uint32 seq
00030 #Two-integer timestamp that is expressed as:
00031 # * stamp.secs: seconds (stamp_secs) since epoch
00032 # * stamp.nsecs: nanoseconds since stamp_secs
00033 # time-handling sugar is provided by the client library
00034 time stamp
00035 #Frame this data is associated with
00036 # 0: no frame
00037 # 1: global frame
00038 string frame_id
00039
00040 ================================================================================
00041 MSG: mod_semantic_map/SemMapObject
00042 # Semantic map object message type, Moritz Tenorth, tenorth@cs.tum.edu
00043 int32 id # unique object identifier
00044 string type # object class: {oven, cupboard, refrigerator, table, countertop, door, hinge, handle, knob, sink}
00045 float32 width # object width
00046 float32 depth # object width
00047 float32 height # object width
00048 float32[] pose # 4x4 pose matrix, row-based
00049 int32 partOf # ID of the parent object (consistent with the ID on the first line)
00050
00051 """
00052 __slots__ = ['map']
00053 _slot_types = ['mod_semantic_map/SemMap']
00054
00055 def __init__(self, *args, **kwds):
00056 """
00057 Constructor. Any message fields that are implicitly/explicitly
00058 set to None will be assigned a default value. The recommend
00059 use is keyword arguments as this is more robust to future message
00060 changes. You cannot mix in-order arguments and keyword arguments.
00061
00062 The available fields are:
00063 map
00064
00065 :param args: complete set of field values, in .msg order
00066 :param kwds: use keyword arguments corresponding to message field names
00067 to set specific fields.
00068 """
00069 if args or kwds:
00070 super(GenerateSemanticMapOWLRequest, self).__init__(*args, **kwds)
00071
00072 if self.map is None:
00073 self.map = mod_semantic_map.msg.SemMap()
00074 else:
00075 self.map = mod_semantic_map.msg.SemMap()
00076
00077 def _get_types(self):
00078 """
00079 internal API method
00080 """
00081 return self._slot_types
00082
00083 def serialize(self, buff):
00084 """
00085 serialize message into buffer
00086 :param buff: buffer, ``StringIO``
00087 """
00088 try:
00089 _x = self
00090 buff.write(_struct_3I.pack(_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs))
00091 _x = self.map.header.frame_id
00092 length = len(_x)
00093 if python3 or type(_x) == unicode:
00094 _x = _x.encode('utf-8')
00095 length = len(_x)
00096 buff.write(struct.pack('<I%ss'%length, length, _x))
00097 length = len(self.map.objects)
00098 buff.write(_struct_I.pack(length))
00099 for val1 in self.map.objects:
00100 buff.write(_struct_i.pack(val1.id))
00101 _x = val1.type
00102 length = len(_x)
00103 if python3 or type(_x) == unicode:
00104 _x = _x.encode('utf-8')
00105 length = len(_x)
00106 buff.write(struct.pack('<I%ss'%length, length, _x))
00107 _x = val1
00108 buff.write(_struct_3f.pack(_x.width, _x.depth, _x.height))
00109 length = len(val1.pose)
00110 buff.write(_struct_I.pack(length))
00111 pattern = '<%sf'%length
00112 buff.write(struct.pack(pattern, *val1.pose))
00113 buff.write(_struct_i.pack(val1.partOf))
00114 except struct.error as se: self._check_types(se)
00115 except TypeError as te: self._check_types(te)
00116
00117 def deserialize(self, str):
00118 """
00119 unpack serialized message in str into this message instance
00120 :param str: byte array of serialized message, ``str``
00121 """
00122 try:
00123 if self.map is None:
00124 self.map = mod_semantic_map.msg.SemMap()
00125 end = 0
00126 _x = self
00127 start = end
00128 end += 12
00129 (_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00130 start = end
00131 end += 4
00132 (length,) = _struct_I.unpack(str[start:end])
00133 start = end
00134 end += length
00135 if python3:
00136 self.map.header.frame_id = str[start:end].decode('utf-8')
00137 else:
00138 self.map.header.frame_id = str[start:end]
00139 start = end
00140 end += 4
00141 (length,) = _struct_I.unpack(str[start:end])
00142 self.map.objects = []
00143 for i in range(0, length):
00144 val1 = mod_semantic_map.msg.SemMapObject()
00145 start = end
00146 end += 4
00147 (val1.id,) = _struct_i.unpack(str[start:end])
00148 start = end
00149 end += 4
00150 (length,) = _struct_I.unpack(str[start:end])
00151 start = end
00152 end += length
00153 if python3:
00154 val1.type = str[start:end].decode('utf-8')
00155 else:
00156 val1.type = str[start:end]
00157 _x = val1
00158 start = end
00159 end += 12
00160 (_x.width, _x.depth, _x.height,) = _struct_3f.unpack(str[start:end])
00161 start = end
00162 end += 4
00163 (length,) = _struct_I.unpack(str[start:end])
00164 pattern = '<%sf'%length
00165 start = end
00166 end += struct.calcsize(pattern)
00167 val1.pose = struct.unpack(pattern, str[start:end])
00168 start = end
00169 end += 4
00170 (val1.partOf,) = _struct_i.unpack(str[start:end])
00171 self.map.objects.append(val1)
00172 return self
00173 except struct.error as e:
00174 raise genpy.DeserializationError(e)
00175
00176
00177 def serialize_numpy(self, buff, numpy):
00178 """
00179 serialize message with numpy array types into buffer
00180 :param buff: buffer, ``StringIO``
00181 :param numpy: numpy python module
00182 """
00183 try:
00184 _x = self
00185 buff.write(_struct_3I.pack(_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs))
00186 _x = self.map.header.frame_id
00187 length = len(_x)
00188 if python3 or type(_x) == unicode:
00189 _x = _x.encode('utf-8')
00190 length = len(_x)
00191 buff.write(struct.pack('<I%ss'%length, length, _x))
00192 length = len(self.map.objects)
00193 buff.write(_struct_I.pack(length))
00194 for val1 in self.map.objects:
00195 buff.write(_struct_i.pack(val1.id))
00196 _x = val1.type
00197 length = len(_x)
00198 if python3 or type(_x) == unicode:
00199 _x = _x.encode('utf-8')
00200 length = len(_x)
00201 buff.write(struct.pack('<I%ss'%length, length, _x))
00202 _x = val1
00203 buff.write(_struct_3f.pack(_x.width, _x.depth, _x.height))
00204 length = len(val1.pose)
00205 buff.write(_struct_I.pack(length))
00206 pattern = '<%sf'%length
00207 buff.write(val1.pose.tostring())
00208 buff.write(_struct_i.pack(val1.partOf))
00209 except struct.error as se: self._check_types(se)
00210 except TypeError as te: self._check_types(te)
00211
00212 def deserialize_numpy(self, str, numpy):
00213 """
00214 unpack serialized message in str into this message instance using numpy for array types
00215 :param str: byte array of serialized message, ``str``
00216 :param numpy: numpy python module
00217 """
00218 try:
00219 if self.map is None:
00220 self.map = mod_semantic_map.msg.SemMap()
00221 end = 0
00222 _x = self
00223 start = end
00224 end += 12
00225 (_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00226 start = end
00227 end += 4
00228 (length,) = _struct_I.unpack(str[start:end])
00229 start = end
00230 end += length
00231 if python3:
00232 self.map.header.frame_id = str[start:end].decode('utf-8')
00233 else:
00234 self.map.header.frame_id = str[start:end]
00235 start = end
00236 end += 4
00237 (length,) = _struct_I.unpack(str[start:end])
00238 self.map.objects = []
00239 for i in range(0, length):
00240 val1 = mod_semantic_map.msg.SemMapObject()
00241 start = end
00242 end += 4
00243 (val1.id,) = _struct_i.unpack(str[start:end])
00244 start = end
00245 end += 4
00246 (length,) = _struct_I.unpack(str[start:end])
00247 start = end
00248 end += length
00249 if python3:
00250 val1.type = str[start:end].decode('utf-8')
00251 else:
00252 val1.type = str[start:end]
00253 _x = val1
00254 start = end
00255 end += 12
00256 (_x.width, _x.depth, _x.height,) = _struct_3f.unpack(str[start:end])
00257 start = end
00258 end += 4
00259 (length,) = _struct_I.unpack(str[start:end])
00260 pattern = '<%sf'%length
00261 start = end
00262 end += struct.calcsize(pattern)
00263 val1.pose = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00264 start = end
00265 end += 4
00266 (val1.partOf,) = _struct_i.unpack(str[start:end])
00267 self.map.objects.append(val1)
00268 return self
00269 except struct.error as e:
00270 raise genpy.DeserializationError(e)
00271
00272 _struct_I = genpy.struct_I
00273 _struct_i = struct.Struct("<i")
00274 _struct_3I = struct.Struct("<3I")
00275 _struct_3f = struct.Struct("<3f")
00276 """autogenerated by genpy from mod_semantic_map/GenerateSemanticMapOWLResponse.msg. Do not edit."""
00277 import sys
00278 python3 = True if sys.hexversion > 0x03000000 else False
00279 import genpy
00280 import struct
00281
00282
00283 class GenerateSemanticMapOWLResponse(genpy.Message):
00284 _md5sum = "dc9efc63bb72e9c68ed58c7eee542724"
00285 _type = "mod_semantic_map/GenerateSemanticMapOWLResponse"
00286 _has_header = False
00287 _full_text = """string owlmap
00288
00289 """
00290 __slots__ = ['owlmap']
00291 _slot_types = ['string']
00292
00293 def __init__(self, *args, **kwds):
00294 """
00295 Constructor. Any message fields that are implicitly/explicitly
00296 set to None will be assigned a default value. The recommend
00297 use is keyword arguments as this is more robust to future message
00298 changes. You cannot mix in-order arguments and keyword arguments.
00299
00300 The available fields are:
00301 owlmap
00302
00303 :param args: complete set of field values, in .msg order
00304 :param kwds: use keyword arguments corresponding to message field names
00305 to set specific fields.
00306 """
00307 if args or kwds:
00308 super(GenerateSemanticMapOWLResponse, self).__init__(*args, **kwds)
00309
00310 if self.owlmap is None:
00311 self.owlmap = ''
00312 else:
00313 self.owlmap = ''
00314
00315 def _get_types(self):
00316 """
00317 internal API method
00318 """
00319 return self._slot_types
00320
00321 def serialize(self, buff):
00322 """
00323 serialize message into buffer
00324 :param buff: buffer, ``StringIO``
00325 """
00326 try:
00327 _x = self.owlmap
00328 length = len(_x)
00329 if python3 or type(_x) == unicode:
00330 _x = _x.encode('utf-8')
00331 length = len(_x)
00332 buff.write(struct.pack('<I%ss'%length, length, _x))
00333 except struct.error as se: self._check_types(se)
00334 except TypeError as te: self._check_types(te)
00335
00336 def deserialize(self, str):
00337 """
00338 unpack serialized message in str into this message instance
00339 :param str: byte array of serialized message, ``str``
00340 """
00341 try:
00342 end = 0
00343 start = end
00344 end += 4
00345 (length,) = _struct_I.unpack(str[start:end])
00346 start = end
00347 end += length
00348 if python3:
00349 self.owlmap = str[start:end].decode('utf-8')
00350 else:
00351 self.owlmap = str[start:end]
00352 return self
00353 except struct.error as e:
00354 raise genpy.DeserializationError(e)
00355
00356
00357 def serialize_numpy(self, buff, numpy):
00358 """
00359 serialize message with numpy array types into buffer
00360 :param buff: buffer, ``StringIO``
00361 :param numpy: numpy python module
00362 """
00363 try:
00364 _x = self.owlmap
00365 length = len(_x)
00366 if python3 or type(_x) == unicode:
00367 _x = _x.encode('utf-8')
00368 length = len(_x)
00369 buff.write(struct.pack('<I%ss'%length, length, _x))
00370 except struct.error as se: self._check_types(se)
00371 except TypeError as te: self._check_types(te)
00372
00373 def deserialize_numpy(self, str, numpy):
00374 """
00375 unpack serialized message in str into this message instance using numpy for array types
00376 :param str: byte array of serialized message, ``str``
00377 :param numpy: numpy python module
00378 """
00379 try:
00380 end = 0
00381 start = end
00382 end += 4
00383 (length,) = _struct_I.unpack(str[start:end])
00384 start = end
00385 end += length
00386 if python3:
00387 self.owlmap = str[start:end].decode('utf-8')
00388 else:
00389 self.owlmap = str[start:end]
00390 return self
00391 except struct.error as e:
00392 raise genpy.DeserializationError(e)
00393
00394 _struct_I = genpy.struct_I
00395 class GenerateSemanticMapOWL(object):
00396 _type = 'mod_semantic_map/GenerateSemanticMapOWL'
00397 _md5sum = 'dd015219cdf33d2d8afec37f8e9fc498'
00398 _request_class = GenerateSemanticMapOWLRequest
00399 _response_class = GenerateSemanticMapOWLResponse