00001 """autogenerated by genpy from interactive_perception_msgs/ObjectSegmentationGuiResult.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 tabletop_object_detector.msg
00008 import sensor_msgs.msg
00009 import geometry_msgs.msg
00010 import shape_msgs.msg
00011 import std_msgs.msg
00012
00013 class ObjectSegmentationGuiResult(genpy.Message):
00014 _md5sum = "ca5ac826b9d0b968e01c52dfce13fecf"
00015 _type = "interactive_perception_msgs/ObjectSegmentationGuiResult"
00016 _has_header = False
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 # The information for the plane that has been detected
00019 tabletop_object_detector/Table table
00020
00021 # The raw clusters detected in the scan
00022 sensor_msgs/PointCloud[] clusters
00023
00024 # Whether the detection has succeeded or failed
00025 int32 NO_CLOUD_RECEIVED = 1
00026 int32 NO_TABLE = 2
00027 int32 OTHER_ERROR = 3
00028 int32 SUCCESS = 4
00029 int32 result
00030
00031
00032 ================================================================================
00033 MSG: tabletop_object_detector/Table
00034 # Informs that a planar table has been detected at a given location
00035
00036 # The pose gives you the transform that take you to the coordinate system
00037 # of the table, with the origin somewhere in the table plane and the
00038 # z axis normal to the plane
00039 geometry_msgs/PoseStamped pose
00040
00041 # These values give you the observed extents of the table, along x and y,
00042 # in the table's own coordinate system (above)
00043 # there is no guarantee that the origin of the table coordinate system is
00044 # inside the boundary defined by these values.
00045 float32 x_min
00046 float32 x_max
00047 float32 y_min
00048 float32 y_max
00049
00050 # There is no guarantee that the table does NOT extend further than these
00051 # values; this is just as far as we've observed it.
00052
00053
00054 # Newer table definition as triangle mesh of convex hull (relative to pose)
00055 shape_msgs/Mesh convex_hull
00056
00057 ================================================================================
00058 MSG: geometry_msgs/PoseStamped
00059 # A Pose with reference coordinate frame and timestamp
00060 Header header
00061 Pose pose
00062
00063 ================================================================================
00064 MSG: std_msgs/Header
00065 # Standard metadata for higher-level stamped data types.
00066 # This is generally used to communicate timestamped data
00067 # in a particular coordinate frame.
00068 #
00069 # sequence ID: consecutively increasing ID
00070 uint32 seq
00071 #Two-integer timestamp that is expressed as:
00072 # * stamp.secs: seconds (stamp_secs) since epoch
00073 # * stamp.nsecs: nanoseconds since stamp_secs
00074 # time-handling sugar is provided by the client library
00075 time stamp
00076 #Frame this data is associated with
00077 # 0: no frame
00078 # 1: global frame
00079 string frame_id
00080
00081 ================================================================================
00082 MSG: geometry_msgs/Pose
00083 # A representation of pose in free space, composed of postion and orientation.
00084 Point position
00085 Quaternion orientation
00086
00087 ================================================================================
00088 MSG: geometry_msgs/Point
00089 # This contains the position of a point in free space
00090 float64 x
00091 float64 y
00092 float64 z
00093
00094 ================================================================================
00095 MSG: geometry_msgs/Quaternion
00096 # This represents an orientation in free space in quaternion form.
00097
00098 float64 x
00099 float64 y
00100 float64 z
00101 float64 w
00102
00103 ================================================================================
00104 MSG: shape_msgs/Mesh
00105 # Definition of a mesh
00106
00107 # list of triangles; the index values refer to positions in vertices[]
00108 MeshTriangle[] triangles
00109
00110 # the actual vertices that make up the mesh
00111 geometry_msgs/Point[] vertices
00112
00113 ================================================================================
00114 MSG: shape_msgs/MeshTriangle
00115 # Definition of a triangle's vertices
00116 uint32[3] vertex_indices
00117
00118 ================================================================================
00119 MSG: sensor_msgs/PointCloud
00120 # This message holds a collection of 3d points, plus optional additional
00121 # information about each point.
00122
00123 # Time of sensor data acquisition, coordinate frame ID.
00124 Header header
00125
00126 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00127 # in the frame given in the header.
00128 geometry_msgs/Point32[] points
00129
00130 # Each channel should have the same number of elements as points array,
00131 # and the data in each channel should correspond 1:1 with each point.
00132 # Channel names in common practice are listed in ChannelFloat32.msg.
00133 ChannelFloat32[] channels
00134
00135 ================================================================================
00136 MSG: geometry_msgs/Point32
00137 # This contains the position of a point in free space(with 32 bits of precision).
00138 # It is recommeded to use Point wherever possible instead of Point32.
00139 #
00140 # This recommendation is to promote interoperability.
00141 #
00142 # This message is designed to take up less space when sending
00143 # lots of points at once, as in the case of a PointCloud.
00144
00145 float32 x
00146 float32 y
00147 float32 z
00148 ================================================================================
00149 MSG: sensor_msgs/ChannelFloat32
00150 # This message is used by the PointCloud message to hold optional data
00151 # associated with each point in the cloud. The length of the values
00152 # array should be the same as the length of the points array in the
00153 # PointCloud, and each value should be associated with the corresponding
00154 # point.
00155
00156 # Channel names in existing practice include:
00157 # "u", "v" - row and column (respectively) in the left stereo image.
00158 # This is opposite to usual conventions but remains for
00159 # historical reasons. The newer PointCloud2 message has no
00160 # such problem.
00161 # "rgb" - For point clouds produced by color stereo cameras. uint8
00162 # (R,G,B) values packed into the least significant 24 bits,
00163 # in order.
00164 # "intensity" - laser or pixel intensity.
00165 # "distance"
00166
00167 # The channel name should give semantics of the channel (e.g.
00168 # "intensity" instead of "value").
00169 string name
00170
00171 # The values array should be 1-1 with the elements of the associated
00172 # PointCloud.
00173 float32[] values
00174
00175 """
00176 # Pseudo-constants
00177 NO_CLOUD_RECEIVED = 1
00178 NO_TABLE = 2
00179 OTHER_ERROR = 3
00180 SUCCESS = 4
00181
00182 __slots__ = ['table','clusters','result']
00183 _slot_types = ['tabletop_object_detector/Table','sensor_msgs/PointCloud[]','int32']
00184
00185 def __init__(self, *args, **kwds):
00186 """
00187 Constructor. Any message fields that are implicitly/explicitly
00188 set to None will be assigned a default value. The recommend
00189 use is keyword arguments as this is more robust to future message
00190 changes. You cannot mix in-order arguments and keyword arguments.
00191
00192 The available fields are:
00193 table,clusters,result
00194
00195 :param args: complete set of field values, in .msg order
00196 :param kwds: use keyword arguments corresponding to message field names
00197 to set specific fields.
00198 """
00199 if args or kwds:
00200 super(ObjectSegmentationGuiResult, self).__init__(*args, **kwds)
00201 #message fields cannot be None, assign default values for those that are
00202 if self.table is None:
00203 self.table = tabletop_object_detector.msg.Table()
00204 if self.clusters is None:
00205 self.clusters = []
00206 if self.result is None:
00207 self.result = 0
00208 else:
00209 self.table = tabletop_object_detector.msg.Table()
00210 self.clusters = []
00211 self.result = 0
00212
00213 def _get_types(self):
00214 """
00215 internal API method
00216 """
00217 return self._slot_types
00218
00219 def serialize(self, buff):
00220 """
00221 serialize message into buffer
00222 :param buff: buffer, ``StringIO``
00223 """
00224 try:
00225 _x = self
00226 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00227 _x = self.table.pose.header.frame_id
00228 length = len(_x)
00229 if python3 or type(_x) == unicode:
00230 _x = _x.encode('utf-8')
00231 length = len(_x)
00232 buff.write(struct.pack('<I%ss'%length, length, _x))
00233 _x = self
00234 buff.write(_struct_7d4f.pack(_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max))
00235 length = len(self.table.convex_hull.triangles)
00236 buff.write(_struct_I.pack(length))
00237 for val1 in self.table.convex_hull.triangles:
00238 buff.write(_struct_3I.pack(*val1.vertex_indices))
00239 length = len(self.table.convex_hull.vertices)
00240 buff.write(_struct_I.pack(length))
00241 for val1 in self.table.convex_hull.vertices:
00242 _x = val1
00243 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00244 length = len(self.clusters)
00245 buff.write(_struct_I.pack(length))
00246 for val1 in self.clusters:
00247 _v1 = val1.header
00248 buff.write(_struct_I.pack(_v1.seq))
00249 _v2 = _v1.stamp
00250 _x = _v2
00251 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00252 _x = _v1.frame_id
00253 length = len(_x)
00254 if python3 or type(_x) == unicode:
00255 _x = _x.encode('utf-8')
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 length = len(val1.points)
00259 buff.write(_struct_I.pack(length))
00260 for val2 in val1.points:
00261 _x = val2
00262 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00263 length = len(val1.channels)
00264 buff.write(_struct_I.pack(length))
00265 for val2 in val1.channels:
00266 _x = val2.name
00267 length = len(_x)
00268 if python3 or type(_x) == unicode:
00269 _x = _x.encode('utf-8')
00270 length = len(_x)
00271 buff.write(struct.pack('<I%ss'%length, length, _x))
00272 length = len(val2.values)
00273 buff.write(_struct_I.pack(length))
00274 pattern = '<%sf'%length
00275 buff.write(struct.pack(pattern, *val2.values))
00276 buff.write(_struct_i.pack(self.result))
00277 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00278 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00279
00280 def deserialize(self, str):
00281 """
00282 unpack serialized message in str into this message instance
00283 :param str: byte array of serialized message, ``str``
00284 """
00285 try:
00286 if self.table is None:
00287 self.table = tabletop_object_detector.msg.Table()
00288 if self.clusters is None:
00289 self.clusters = None
00290 end = 0
00291 _x = self
00292 start = end
00293 end += 12
00294 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00295 start = end
00296 end += 4
00297 (length,) = _struct_I.unpack(str[start:end])
00298 start = end
00299 end += length
00300 if python3:
00301 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00302 else:
00303 self.table.pose.header.frame_id = str[start:end]
00304 _x = self
00305 start = end
00306 end += 72
00307 (_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00308 start = end
00309 end += 4
00310 (length,) = _struct_I.unpack(str[start:end])
00311 self.table.convex_hull.triangles = []
00312 for i in range(0, length):
00313 val1 = shape_msgs.msg.MeshTriangle()
00314 start = end
00315 end += 12
00316 val1.vertex_indices = _struct_3I.unpack(str[start:end])
00317 self.table.convex_hull.triangles.append(val1)
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 self.table.convex_hull.vertices = []
00322 for i in range(0, length):
00323 val1 = geometry_msgs.msg.Point()
00324 _x = val1
00325 start = end
00326 end += 24
00327 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00328 self.table.convex_hull.vertices.append(val1)
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 self.clusters = []
00333 for i in range(0, length):
00334 val1 = sensor_msgs.msg.PointCloud()
00335 _v3 = val1.header
00336 start = end
00337 end += 4
00338 (_v3.seq,) = _struct_I.unpack(str[start:end])
00339 _v4 = _v3.stamp
00340 _x = _v4
00341 start = end
00342 end += 8
00343 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00344 start = end
00345 end += 4
00346 (length,) = _struct_I.unpack(str[start:end])
00347 start = end
00348 end += length
00349 if python3:
00350 _v3.frame_id = str[start:end].decode('utf-8')
00351 else:
00352 _v3.frame_id = str[start:end]
00353 start = end
00354 end += 4
00355 (length,) = _struct_I.unpack(str[start:end])
00356 val1.points = []
00357 for i in range(0, length):
00358 val2 = geometry_msgs.msg.Point32()
00359 _x = val2
00360 start = end
00361 end += 12
00362 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00363 val1.points.append(val2)
00364 start = end
00365 end += 4
00366 (length,) = _struct_I.unpack(str[start:end])
00367 val1.channels = []
00368 for i in range(0, length):
00369 val2 = sensor_msgs.msg.ChannelFloat32()
00370 start = end
00371 end += 4
00372 (length,) = _struct_I.unpack(str[start:end])
00373 start = end
00374 end += length
00375 if python3:
00376 val2.name = str[start:end].decode('utf-8')
00377 else:
00378 val2.name = str[start:end]
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 pattern = '<%sf'%length
00383 start = end
00384 end += struct.calcsize(pattern)
00385 val2.values = struct.unpack(pattern, str[start:end])
00386 val1.channels.append(val2)
00387 self.clusters.append(val1)
00388 start = end
00389 end += 4
00390 (self.result,) = _struct_i.unpack(str[start:end])
00391 return self
00392 except struct.error as e:
00393 raise genpy.DeserializationError(e) #most likely buffer underfill
00394
00395
00396 def serialize_numpy(self, buff, numpy):
00397 """
00398 serialize message with numpy array types into buffer
00399 :param buff: buffer, ``StringIO``
00400 :param numpy: numpy python module
00401 """
00402 try:
00403 _x = self
00404 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00405 _x = self.table.pose.header.frame_id
00406 length = len(_x)
00407 if python3 or type(_x) == unicode:
00408 _x = _x.encode('utf-8')
00409 length = len(_x)
00410 buff.write(struct.pack('<I%ss'%length, length, _x))
00411 _x = self
00412 buff.write(_struct_7d4f.pack(_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max))
00413 length = len(self.table.convex_hull.triangles)
00414 buff.write(_struct_I.pack(length))
00415 for val1 in self.table.convex_hull.triangles:
00416 buff.write(val1.vertex_indices.tostring())
00417 length = len(self.table.convex_hull.vertices)
00418 buff.write(_struct_I.pack(length))
00419 for val1 in self.table.convex_hull.vertices:
00420 _x = val1
00421 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00422 length = len(self.clusters)
00423 buff.write(_struct_I.pack(length))
00424 for val1 in self.clusters:
00425 _v5 = val1.header
00426 buff.write(_struct_I.pack(_v5.seq))
00427 _v6 = _v5.stamp
00428 _x = _v6
00429 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00430 _x = _v5.frame_id
00431 length = len(_x)
00432 if python3 or type(_x) == unicode:
00433 _x = _x.encode('utf-8')
00434 length = len(_x)
00435 buff.write(struct.pack('<I%ss'%length, length, _x))
00436 length = len(val1.points)
00437 buff.write(_struct_I.pack(length))
00438 for val2 in val1.points:
00439 _x = val2
00440 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00441 length = len(val1.channels)
00442 buff.write(_struct_I.pack(length))
00443 for val2 in val1.channels:
00444 _x = val2.name
00445 length = len(_x)
00446 if python3 or type(_x) == unicode:
00447 _x = _x.encode('utf-8')
00448 length = len(_x)
00449 buff.write(struct.pack('<I%ss'%length, length, _x))
00450 length = len(val2.values)
00451 buff.write(_struct_I.pack(length))
00452 pattern = '<%sf'%length
00453 buff.write(val2.values.tostring())
00454 buff.write(_struct_i.pack(self.result))
00455 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00456 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00457
00458 def deserialize_numpy(self, str, numpy):
00459 """
00460 unpack serialized message in str into this message instance using numpy for array types
00461 :param str: byte array of serialized message, ``str``
00462 :param numpy: numpy python module
00463 """
00464 try:
00465 if self.table is None:
00466 self.table = tabletop_object_detector.msg.Table()
00467 if self.clusters is None:
00468 self.clusters = None
00469 end = 0
00470 _x = self
00471 start = end
00472 end += 12
00473 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00474 start = end
00475 end += 4
00476 (length,) = _struct_I.unpack(str[start:end])
00477 start = end
00478 end += length
00479 if python3:
00480 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00481 else:
00482 self.table.pose.header.frame_id = str[start:end]
00483 _x = self
00484 start = end
00485 end += 72
00486 (_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00487 start = end
00488 end += 4
00489 (length,) = _struct_I.unpack(str[start:end])
00490 self.table.convex_hull.triangles = []
00491 for i in range(0, length):
00492 val1 = shape_msgs.msg.MeshTriangle()
00493 start = end
00494 end += 12
00495 val1.vertex_indices = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=3)
00496 self.table.convex_hull.triangles.append(val1)
00497 start = end
00498 end += 4
00499 (length,) = _struct_I.unpack(str[start:end])
00500 self.table.convex_hull.vertices = []
00501 for i in range(0, length):
00502 val1 = geometry_msgs.msg.Point()
00503 _x = val1
00504 start = end
00505 end += 24
00506 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00507 self.table.convex_hull.vertices.append(val1)
00508 start = end
00509 end += 4
00510 (length,) = _struct_I.unpack(str[start:end])
00511 self.clusters = []
00512 for i in range(0, length):
00513 val1 = sensor_msgs.msg.PointCloud()
00514 _v7 = val1.header
00515 start = end
00516 end += 4
00517 (_v7.seq,) = _struct_I.unpack(str[start:end])
00518 _v8 = _v7.stamp
00519 _x = _v8
00520 start = end
00521 end += 8
00522 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00523 start = end
00524 end += 4
00525 (length,) = _struct_I.unpack(str[start:end])
00526 start = end
00527 end += length
00528 if python3:
00529 _v7.frame_id = str[start:end].decode('utf-8')
00530 else:
00531 _v7.frame_id = str[start:end]
00532 start = end
00533 end += 4
00534 (length,) = _struct_I.unpack(str[start:end])
00535 val1.points = []
00536 for i in range(0, length):
00537 val2 = geometry_msgs.msg.Point32()
00538 _x = val2
00539 start = end
00540 end += 12
00541 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00542 val1.points.append(val2)
00543 start = end
00544 end += 4
00545 (length,) = _struct_I.unpack(str[start:end])
00546 val1.channels = []
00547 for i in range(0, length):
00548 val2 = sensor_msgs.msg.ChannelFloat32()
00549 start = end
00550 end += 4
00551 (length,) = _struct_I.unpack(str[start:end])
00552 start = end
00553 end += length
00554 if python3:
00555 val2.name = str[start:end].decode('utf-8')
00556 else:
00557 val2.name = str[start:end]
00558 start = end
00559 end += 4
00560 (length,) = _struct_I.unpack(str[start:end])
00561 pattern = '<%sf'%length
00562 start = end
00563 end += struct.calcsize(pattern)
00564 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00565 val1.channels.append(val2)
00566 self.clusters.append(val1)
00567 start = end
00568 end += 4
00569 (self.result,) = _struct_i.unpack(str[start:end])
00570 return self
00571 except struct.error as e:
00572 raise genpy.DeserializationError(e) #most likely buffer underfill
00573
00574 _struct_I = genpy.struct_I
00575 _struct_7d4f = struct.Struct("<7d4f")
00576 _struct_2I = struct.Struct("<2I")
00577 _struct_i = struct.Struct("<i")
00578 _struct_3I = struct.Struct("<3I")
00579 _struct_3f = struct.Struct("<3f")
00580 _struct_3d = struct.Struct("<3d")