00001 """autogenerated by genpy from object_segmentation_gui/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 arm_navigation_msgs.msg
00008 import tabletop_object_detector.msg
00009 import sensor_msgs.msg
00010 import geometry_msgs.msg
00011 import std_msgs.msg
00012
00013 class ObjectSegmentationGuiResult(genpy.Message):
00014 _md5sum = "1ece7d86360ba38c12673652ea654b18"
00015 _type = "object_segmentation_gui/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 arm_navigation_msgs/Shape 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: arm_navigation_msgs/Shape
00105 byte SPHERE=0
00106 byte BOX=1
00107 byte CYLINDER=2
00108 byte MESH=3
00109
00110 byte type
00111
00112
00113 #### define sphere, box, cylinder ####
00114 # the origin of each shape is considered at the shape's center
00115
00116 # for sphere
00117 # radius := dimensions[0]
00118
00119 # for cylinder
00120 # radius := dimensions[0]
00121 # length := dimensions[1]
00122 # the length is along the Z axis
00123
00124 # for box
00125 # size_x := dimensions[0]
00126 # size_y := dimensions[1]
00127 # size_z := dimensions[2]
00128 float64[] dimensions
00129
00130
00131 #### define mesh ####
00132
00133 # list of triangles; triangle k is defined by tre vertices located
00134 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00135 int32[] triangles
00136 geometry_msgs/Point[] vertices
00137
00138 ================================================================================
00139 MSG: sensor_msgs/PointCloud
00140 # This message holds a collection of 3d points, plus optional additional
00141 # information about each point.
00142
00143 # Time of sensor data acquisition, coordinate frame ID.
00144 Header header
00145
00146 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00147 # in the frame given in the header.
00148 geometry_msgs/Point32[] points
00149
00150 # Each channel should have the same number of elements as points array,
00151 # and the data in each channel should correspond 1:1 with each point.
00152 # Channel names in common practice are listed in ChannelFloat32.msg.
00153 ChannelFloat32[] channels
00154
00155 ================================================================================
00156 MSG: geometry_msgs/Point32
00157 # This contains the position of a point in free space(with 32 bits of precision).
00158 # It is recommeded to use Point wherever possible instead of Point32.
00159 #
00160 # This recommendation is to promote interoperability.
00161 #
00162 # This message is designed to take up less space when sending
00163 # lots of points at once, as in the case of a PointCloud.
00164
00165 float32 x
00166 float32 y
00167 float32 z
00168 ================================================================================
00169 MSG: sensor_msgs/ChannelFloat32
00170 # This message is used by the PointCloud message to hold optional data
00171 # associated with each point in the cloud. The length of the values
00172 # array should be the same as the length of the points array in the
00173 # PointCloud, and each value should be associated with the corresponding
00174 # point.
00175
00176 # Channel names in existing practice include:
00177 # "u", "v" - row and column (respectively) in the left stereo image.
00178 # This is opposite to usual conventions but remains for
00179 # historical reasons. The newer PointCloud2 message has no
00180 # such problem.
00181 # "rgb" - For point clouds produced by color stereo cameras. uint8
00182 # (R,G,B) values packed into the least significant 24 bits,
00183 # in order.
00184 # "intensity" - laser or pixel intensity.
00185 # "distance"
00186
00187 # The channel name should give semantics of the channel (e.g.
00188 # "intensity" instead of "value").
00189 string name
00190
00191 # The values array should be 1-1 with the elements of the associated
00192 # PointCloud.
00193 float32[] values
00194
00195 """
00196 # Pseudo-constants
00197 NO_CLOUD_RECEIVED = 1
00198 NO_TABLE = 2
00199 OTHER_ERROR = 3
00200 SUCCESS = 4
00201
00202 __slots__ = ['table','clusters','result']
00203 _slot_types = ['tabletop_object_detector/Table','sensor_msgs/PointCloud[]','int32']
00204
00205 def __init__(self, *args, **kwds):
00206 """
00207 Constructor. Any message fields that are implicitly/explicitly
00208 set to None will be assigned a default value. The recommend
00209 use is keyword arguments as this is more robust to future message
00210 changes. You cannot mix in-order arguments and keyword arguments.
00211
00212 The available fields are:
00213 table,clusters,result
00214
00215 :param args: complete set of field values, in .msg order
00216 :param kwds: use keyword arguments corresponding to message field names
00217 to set specific fields.
00218 """
00219 if args or kwds:
00220 super(ObjectSegmentationGuiResult, self).__init__(*args, **kwds)
00221 #message fields cannot be None, assign default values for those that are
00222 if self.table is None:
00223 self.table = tabletop_object_detector.msg.Table()
00224 if self.clusters is None:
00225 self.clusters = []
00226 if self.result is None:
00227 self.result = 0
00228 else:
00229 self.table = tabletop_object_detector.msg.Table()
00230 self.clusters = []
00231 self.result = 0
00232
00233 def _get_types(self):
00234 """
00235 internal API method
00236 """
00237 return self._slot_types
00238
00239 def serialize(self, buff):
00240 """
00241 serialize message into buffer
00242 :param buff: buffer, ``StringIO``
00243 """
00244 try:
00245 _x = self
00246 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00247 _x = self.table.pose.header.frame_id
00248 length = len(_x)
00249 if python3 or type(_x) == unicode:
00250 _x = _x.encode('utf-8')
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_7d4fb.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, _x.table.convex_hull.type))
00255 length = len(self.table.convex_hull.dimensions)
00256 buff.write(_struct_I.pack(length))
00257 pattern = '<%sd'%length
00258 buff.write(struct.pack(pattern, *self.table.convex_hull.dimensions))
00259 length = len(self.table.convex_hull.triangles)
00260 buff.write(_struct_I.pack(length))
00261 pattern = '<%si'%length
00262 buff.write(struct.pack(pattern, *self.table.convex_hull.triangles))
00263 length = len(self.table.convex_hull.vertices)
00264 buff.write(_struct_I.pack(length))
00265 for val1 in self.table.convex_hull.vertices:
00266 _x = val1
00267 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00268 length = len(self.clusters)
00269 buff.write(_struct_I.pack(length))
00270 for val1 in self.clusters:
00271 _v1 = val1.header
00272 buff.write(_struct_I.pack(_v1.seq))
00273 _v2 = _v1.stamp
00274 _x = _v2
00275 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00276 _x = _v1.frame_id
00277 length = len(_x)
00278 if python3 or type(_x) == unicode:
00279 _x = _x.encode('utf-8')
00280 length = len(_x)
00281 buff.write(struct.pack('<I%ss'%length, length, _x))
00282 length = len(val1.points)
00283 buff.write(_struct_I.pack(length))
00284 for val2 in val1.points:
00285 _x = val2
00286 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00287 length = len(val1.channels)
00288 buff.write(_struct_I.pack(length))
00289 for val2 in val1.channels:
00290 _x = val2.name
00291 length = len(_x)
00292 if python3 or type(_x) == unicode:
00293 _x = _x.encode('utf-8')
00294 length = len(_x)
00295 buff.write(struct.pack('<I%ss'%length, length, _x))
00296 length = len(val2.values)
00297 buff.write(_struct_I.pack(length))
00298 pattern = '<%sf'%length
00299 buff.write(struct.pack(pattern, *val2.values))
00300 buff.write(_struct_i.pack(self.result))
00301 except struct.error as se: self._check_types(se)
00302 except TypeError as te: self._check_types(te)
00303
00304 def deserialize(self, str):
00305 """
00306 unpack serialized message in str into this message instance
00307 :param str: byte array of serialized message, ``str``
00308 """
00309 try:
00310 if self.table is None:
00311 self.table = tabletop_object_detector.msg.Table()
00312 if self.clusters is None:
00313 self.clusters = None
00314 end = 0
00315 _x = self
00316 start = end
00317 end += 12
00318 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00319 start = end
00320 end += 4
00321 (length,) = _struct_I.unpack(str[start:end])
00322 start = end
00323 end += length
00324 if python3:
00325 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00326 else:
00327 self.table.pose.header.frame_id = str[start:end]
00328 _x = self
00329 start = end
00330 end += 73
00331 (_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, _x.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 pattern = '<%sd'%length
00336 start = end
00337 end += struct.calcsize(pattern)
00338 self.table.convex_hull.dimensions = struct.unpack(pattern, str[start:end])
00339 start = end
00340 end += 4
00341 (length,) = _struct_I.unpack(str[start:end])
00342 pattern = '<%si'%length
00343 start = end
00344 end += struct.calcsize(pattern)
00345 self.table.convex_hull.triangles = struct.unpack(pattern, str[start:end])
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 self.table.convex_hull.vertices = []
00350 for i in range(0, length):
00351 val1 = geometry_msgs.msg.Point()
00352 _x = val1
00353 start = end
00354 end += 24
00355 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00356 self.table.convex_hull.vertices.append(val1)
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 self.clusters = []
00361 for i in range(0, length):
00362 val1 = sensor_msgs.msg.PointCloud()
00363 _v3 = val1.header
00364 start = end
00365 end += 4
00366 (_v3.seq,) = _struct_I.unpack(str[start:end])
00367 _v4 = _v3.stamp
00368 _x = _v4
00369 start = end
00370 end += 8
00371 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00372 start = end
00373 end += 4
00374 (length,) = _struct_I.unpack(str[start:end])
00375 start = end
00376 end += length
00377 if python3:
00378 _v3.frame_id = str[start:end].decode('utf-8')
00379 else:
00380 _v3.frame_id = str[start:end]
00381 start = end
00382 end += 4
00383 (length,) = _struct_I.unpack(str[start:end])
00384 val1.points = []
00385 for i in range(0, length):
00386 val2 = geometry_msgs.msg.Point32()
00387 _x = val2
00388 start = end
00389 end += 12
00390 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00391 val1.points.append(val2)
00392 start = end
00393 end += 4
00394 (length,) = _struct_I.unpack(str[start:end])
00395 val1.channels = []
00396 for i in range(0, length):
00397 val2 = sensor_msgs.msg.ChannelFloat32()
00398 start = end
00399 end += 4
00400 (length,) = _struct_I.unpack(str[start:end])
00401 start = end
00402 end += length
00403 if python3:
00404 val2.name = str[start:end].decode('utf-8')
00405 else:
00406 val2.name = str[start:end]
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 pattern = '<%sf'%length
00411 start = end
00412 end += struct.calcsize(pattern)
00413 val2.values = struct.unpack(pattern, str[start:end])
00414 val1.channels.append(val2)
00415 self.clusters.append(val1)
00416 start = end
00417 end += 4
00418 (self.result,) = _struct_i.unpack(str[start:end])
00419 return self
00420 except struct.error as e:
00421 raise genpy.DeserializationError(e) #most likely buffer underfill
00422
00423
00424 def serialize_numpy(self, buff, numpy):
00425 """
00426 serialize message with numpy array types into buffer
00427 :param buff: buffer, ``StringIO``
00428 :param numpy: numpy python module
00429 """
00430 try:
00431 _x = self
00432 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00433 _x = self.table.pose.header.frame_id
00434 length = len(_x)
00435 if python3 or type(_x) == unicode:
00436 _x = _x.encode('utf-8')
00437 length = len(_x)
00438 buff.write(struct.pack('<I%ss'%length, length, _x))
00439 _x = self
00440 buff.write(_struct_7d4fb.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, _x.table.convex_hull.type))
00441 length = len(self.table.convex_hull.dimensions)
00442 buff.write(_struct_I.pack(length))
00443 pattern = '<%sd'%length
00444 buff.write(self.table.convex_hull.dimensions.tostring())
00445 length = len(self.table.convex_hull.triangles)
00446 buff.write(_struct_I.pack(length))
00447 pattern = '<%si'%length
00448 buff.write(self.table.convex_hull.triangles.tostring())
00449 length = len(self.table.convex_hull.vertices)
00450 buff.write(_struct_I.pack(length))
00451 for val1 in self.table.convex_hull.vertices:
00452 _x = val1
00453 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00454 length = len(self.clusters)
00455 buff.write(_struct_I.pack(length))
00456 for val1 in self.clusters:
00457 _v5 = val1.header
00458 buff.write(_struct_I.pack(_v5.seq))
00459 _v6 = _v5.stamp
00460 _x = _v6
00461 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00462 _x = _v5.frame_id
00463 length = len(_x)
00464 if python3 or type(_x) == unicode:
00465 _x = _x.encode('utf-8')
00466 length = len(_x)
00467 buff.write(struct.pack('<I%ss'%length, length, _x))
00468 length = len(val1.points)
00469 buff.write(_struct_I.pack(length))
00470 for val2 in val1.points:
00471 _x = val2
00472 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00473 length = len(val1.channels)
00474 buff.write(_struct_I.pack(length))
00475 for val2 in val1.channels:
00476 _x = val2.name
00477 length = len(_x)
00478 if python3 or type(_x) == unicode:
00479 _x = _x.encode('utf-8')
00480 length = len(_x)
00481 buff.write(struct.pack('<I%ss'%length, length, _x))
00482 length = len(val2.values)
00483 buff.write(_struct_I.pack(length))
00484 pattern = '<%sf'%length
00485 buff.write(val2.values.tostring())
00486 buff.write(_struct_i.pack(self.result))
00487 except struct.error as se: self._check_types(se)
00488 except TypeError as te: self._check_types(te)
00489
00490 def deserialize_numpy(self, str, numpy):
00491 """
00492 unpack serialized message in str into this message instance using numpy for array types
00493 :param str: byte array of serialized message, ``str``
00494 :param numpy: numpy python module
00495 """
00496 try:
00497 if self.table is None:
00498 self.table = tabletop_object_detector.msg.Table()
00499 if self.clusters is None:
00500 self.clusters = None
00501 end = 0
00502 _x = self
00503 start = end
00504 end += 12
00505 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00506 start = end
00507 end += 4
00508 (length,) = _struct_I.unpack(str[start:end])
00509 start = end
00510 end += length
00511 if python3:
00512 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00513 else:
00514 self.table.pose.header.frame_id = str[start:end]
00515 _x = self
00516 start = end
00517 end += 73
00518 (_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, _x.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
00519 start = end
00520 end += 4
00521 (length,) = _struct_I.unpack(str[start:end])
00522 pattern = '<%sd'%length
00523 start = end
00524 end += struct.calcsize(pattern)
00525 self.table.convex_hull.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 pattern = '<%si'%length
00530 start = end
00531 end += struct.calcsize(pattern)
00532 self.table.convex_hull.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00533 start = end
00534 end += 4
00535 (length,) = _struct_I.unpack(str[start:end])
00536 self.table.convex_hull.vertices = []
00537 for i in range(0, length):
00538 val1 = geometry_msgs.msg.Point()
00539 _x = val1
00540 start = end
00541 end += 24
00542 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00543 self.table.convex_hull.vertices.append(val1)
00544 start = end
00545 end += 4
00546 (length,) = _struct_I.unpack(str[start:end])
00547 self.clusters = []
00548 for i in range(0, length):
00549 val1 = sensor_msgs.msg.PointCloud()
00550 _v7 = val1.header
00551 start = end
00552 end += 4
00553 (_v7.seq,) = _struct_I.unpack(str[start:end])
00554 _v8 = _v7.stamp
00555 _x = _v8
00556 start = end
00557 end += 8
00558 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00559 start = end
00560 end += 4
00561 (length,) = _struct_I.unpack(str[start:end])
00562 start = end
00563 end += length
00564 if python3:
00565 _v7.frame_id = str[start:end].decode('utf-8')
00566 else:
00567 _v7.frame_id = str[start:end]
00568 start = end
00569 end += 4
00570 (length,) = _struct_I.unpack(str[start:end])
00571 val1.points = []
00572 for i in range(0, length):
00573 val2 = geometry_msgs.msg.Point32()
00574 _x = val2
00575 start = end
00576 end += 12
00577 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00578 val1.points.append(val2)
00579 start = end
00580 end += 4
00581 (length,) = _struct_I.unpack(str[start:end])
00582 val1.channels = []
00583 for i in range(0, length):
00584 val2 = sensor_msgs.msg.ChannelFloat32()
00585 start = end
00586 end += 4
00587 (length,) = _struct_I.unpack(str[start:end])
00588 start = end
00589 end += length
00590 if python3:
00591 val2.name = str[start:end].decode('utf-8')
00592 else:
00593 val2.name = str[start:end]
00594 start = end
00595 end += 4
00596 (length,) = _struct_I.unpack(str[start:end])
00597 pattern = '<%sf'%length
00598 start = end
00599 end += struct.calcsize(pattern)
00600 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00601 val1.channels.append(val2)
00602 self.clusters.append(val1)
00603 start = end
00604 end += 4
00605 (self.result,) = _struct_i.unpack(str[start:end])
00606 return self
00607 except struct.error as e:
00608 raise genpy.DeserializationError(e) #most likely buffer underfill
00609
00610 _struct_I = genpy.struct_I
00611 _struct_7d4fb = struct.Struct("<7d4fb")
00612 _struct_2I = struct.Struct("<2I")
00613 _struct_i = struct.Struct("<i")
00614 _struct_3I = struct.Struct("<3I")
00615 _struct_3f = struct.Struct("<3f")
00616 _struct_3d = struct.Struct("<3d")