00001 """autogenerated by genpy from tabletop_object_detector/TabletopSegmentationRequest.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 geometry_msgs.msg
00010 import std_msgs.msg
00011
00012 class TabletopSegmentationRequest(genpy.Message):
00013 _md5sum = "eb8b1c91882b1925278d37d3e15fd20a"
00014 _type = "tabletop_object_detector/TabletopSegmentationRequest"
00015 _has_header = False
00016 _full_text = """
00017
00018
00019 Table table
00020
00021
00022 ================================================================================
00023 MSG: tabletop_object_detector/Table
00024 # Informs that a planar table has been detected at a given location
00025
00026 # The pose gives you the transform that take you to the coordinate system
00027 # of the table, with the origin somewhere in the table plane and the
00028 # z axis normal to the plane
00029 geometry_msgs/PoseStamped pose
00030
00031 # These values give you the observed extents of the table, along x and y,
00032 # in the table's own coordinate system (above)
00033 # there is no guarantee that the origin of the table coordinate system is
00034 # inside the boundary defined by these values.
00035 float32 x_min
00036 float32 x_max
00037 float32 y_min
00038 float32 y_max
00039
00040 # There is no guarantee that the table does NOT extend further than these
00041 # values; this is just as far as we've observed it.
00042
00043
00044 # Newer table definition as triangle mesh of convex hull (relative to pose)
00045 arm_navigation_msgs/Shape convex_hull
00046
00047 ================================================================================
00048 MSG: geometry_msgs/PoseStamped
00049 # A Pose with reference coordinate frame and timestamp
00050 Header header
00051 Pose pose
00052
00053 ================================================================================
00054 MSG: std_msgs/Header
00055 # Standard metadata for higher-level stamped data types.
00056 # This is generally used to communicate timestamped data
00057 # in a particular coordinate frame.
00058 #
00059 # sequence ID: consecutively increasing ID
00060 uint32 seq
00061 #Two-integer timestamp that is expressed as:
00062 # * stamp.secs: seconds (stamp_secs) since epoch
00063 # * stamp.nsecs: nanoseconds since stamp_secs
00064 # time-handling sugar is provided by the client library
00065 time stamp
00066 #Frame this data is associated with
00067 # 0: no frame
00068 # 1: global frame
00069 string frame_id
00070
00071 ================================================================================
00072 MSG: geometry_msgs/Pose
00073 # A representation of pose in free space, composed of postion and orientation.
00074 Point position
00075 Quaternion orientation
00076
00077 ================================================================================
00078 MSG: geometry_msgs/Point
00079 # This contains the position of a point in free space
00080 float64 x
00081 float64 y
00082 float64 z
00083
00084 ================================================================================
00085 MSG: geometry_msgs/Quaternion
00086 # This represents an orientation in free space in quaternion form.
00087
00088 float64 x
00089 float64 y
00090 float64 z
00091 float64 w
00092
00093 ================================================================================
00094 MSG: arm_navigation_msgs/Shape
00095 byte SPHERE=0
00096 byte BOX=1
00097 byte CYLINDER=2
00098 byte MESH=3
00099
00100 byte type
00101
00102
00103 #### define sphere, box, cylinder ####
00104 # the origin of each shape is considered at the shape's center
00105
00106 # for sphere
00107 # radius := dimensions[0]
00108
00109 # for cylinder
00110 # radius := dimensions[0]
00111 # length := dimensions[1]
00112 # the length is along the Z axis
00113
00114 # for box
00115 # size_x := dimensions[0]
00116 # size_y := dimensions[1]
00117 # size_z := dimensions[2]
00118 float64[] dimensions
00119
00120
00121 #### define mesh ####
00122
00123 # list of triangles; triangle k is defined by tre vertices located
00124 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00125 int32[] triangles
00126 geometry_msgs/Point[] vertices
00127
00128 """
00129 __slots__ = ['table']
00130 _slot_types = ['tabletop_object_detector/Table']
00131
00132 def __init__(self, *args, **kwds):
00133 """
00134 Constructor. Any message fields that are implicitly/explicitly
00135 set to None will be assigned a default value. The recommend
00136 use is keyword arguments as this is more robust to future message
00137 changes. You cannot mix in-order arguments and keyword arguments.
00138
00139 The available fields are:
00140 table
00141
00142 :param args: complete set of field values, in .msg order
00143 :param kwds: use keyword arguments corresponding to message field names
00144 to set specific fields.
00145 """
00146 if args or kwds:
00147 super(TabletopSegmentationRequest, self).__init__(*args, **kwds)
00148
00149 if self.table is None:
00150 self.table = tabletop_object_detector.msg.Table()
00151 else:
00152 self.table = tabletop_object_detector.msg.Table()
00153
00154 def _get_types(self):
00155 """
00156 internal API method
00157 """
00158 return self._slot_types
00159
00160 def serialize(self, buff):
00161 """
00162 serialize message into buffer
00163 :param buff: buffer, ``StringIO``
00164 """
00165 try:
00166 _x = self
00167 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00168 _x = self.table.pose.header.frame_id
00169 length = len(_x)
00170 if python3 or type(_x) == unicode:
00171 _x = _x.encode('utf-8')
00172 length = len(_x)
00173 buff.write(struct.pack('<I%ss'%length, length, _x))
00174 _x = self
00175 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))
00176 length = len(self.table.convex_hull.dimensions)
00177 buff.write(_struct_I.pack(length))
00178 pattern = '<%sd'%length
00179 buff.write(struct.pack(pattern, *self.table.convex_hull.dimensions))
00180 length = len(self.table.convex_hull.triangles)
00181 buff.write(_struct_I.pack(length))
00182 pattern = '<%si'%length
00183 buff.write(struct.pack(pattern, *self.table.convex_hull.triangles))
00184 length = len(self.table.convex_hull.vertices)
00185 buff.write(_struct_I.pack(length))
00186 for val1 in self.table.convex_hull.vertices:
00187 _x = val1
00188 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00189 except struct.error as se: self._check_types(se)
00190 except TypeError as te: self._check_types(te)
00191
00192 def deserialize(self, str):
00193 """
00194 unpack serialized message in str into this message instance
00195 :param str: byte array of serialized message, ``str``
00196 """
00197 try:
00198 if self.table is None:
00199 self.table = tabletop_object_detector.msg.Table()
00200 end = 0
00201 _x = self
00202 start = end
00203 end += 12
00204 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += length
00210 if python3:
00211 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00212 else:
00213 self.table.pose.header.frame_id = str[start:end]
00214 _x = self
00215 start = end
00216 end += 73
00217 (_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])
00218 start = end
00219 end += 4
00220 (length,) = _struct_I.unpack(str[start:end])
00221 pattern = '<%sd'%length
00222 start = end
00223 end += struct.calcsize(pattern)
00224 self.table.convex_hull.dimensions = struct.unpack(pattern, str[start:end])
00225 start = end
00226 end += 4
00227 (length,) = _struct_I.unpack(str[start:end])
00228 pattern = '<%si'%length
00229 start = end
00230 end += struct.calcsize(pattern)
00231 self.table.convex_hull.triangles = struct.unpack(pattern, str[start:end])
00232 start = end
00233 end += 4
00234 (length,) = _struct_I.unpack(str[start:end])
00235 self.table.convex_hull.vertices = []
00236 for i in range(0, length):
00237 val1 = geometry_msgs.msg.Point()
00238 _x = val1
00239 start = end
00240 end += 24
00241 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00242 self.table.convex_hull.vertices.append(val1)
00243 return self
00244 except struct.error as e:
00245 raise genpy.DeserializationError(e)
00246
00247
00248 def serialize_numpy(self, buff, numpy):
00249 """
00250 serialize message with numpy array types into buffer
00251 :param buff: buffer, ``StringIO``
00252 :param numpy: numpy python module
00253 """
00254 try:
00255 _x = self
00256 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00257 _x = self.table.pose.header.frame_id
00258 length = len(_x)
00259 if python3 or type(_x) == unicode:
00260 _x = _x.encode('utf-8')
00261 length = len(_x)
00262 buff.write(struct.pack('<I%ss'%length, length, _x))
00263 _x = self
00264 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))
00265 length = len(self.table.convex_hull.dimensions)
00266 buff.write(_struct_I.pack(length))
00267 pattern = '<%sd'%length
00268 buff.write(self.table.convex_hull.dimensions.tostring())
00269 length = len(self.table.convex_hull.triangles)
00270 buff.write(_struct_I.pack(length))
00271 pattern = '<%si'%length
00272 buff.write(self.table.convex_hull.triangles.tostring())
00273 length = len(self.table.convex_hull.vertices)
00274 buff.write(_struct_I.pack(length))
00275 for val1 in self.table.convex_hull.vertices:
00276 _x = val1
00277 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00278 except struct.error as se: self._check_types(se)
00279 except TypeError as te: self._check_types(te)
00280
00281 def deserialize_numpy(self, str, numpy):
00282 """
00283 unpack serialized message in str into this message instance using numpy for array types
00284 :param str: byte array of serialized message, ``str``
00285 :param numpy: numpy python module
00286 """
00287 try:
00288 if self.table is None:
00289 self.table = tabletop_object_detector.msg.Table()
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 += 73
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, _x.table.convex_hull.type,) = _struct_7d4fb.unpack(str[start:end])
00308 start = end
00309 end += 4
00310 (length,) = _struct_I.unpack(str[start:end])
00311 pattern = '<%sd'%length
00312 start = end
00313 end += struct.calcsize(pattern)
00314 self.table.convex_hull.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 pattern = '<%si'%length
00319 start = end
00320 end += struct.calcsize(pattern)
00321 self.table.convex_hull.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00322 start = end
00323 end += 4
00324 (length,) = _struct_I.unpack(str[start:end])
00325 self.table.convex_hull.vertices = []
00326 for i in range(0, length):
00327 val1 = geometry_msgs.msg.Point()
00328 _x = val1
00329 start = end
00330 end += 24
00331 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00332 self.table.convex_hull.vertices.append(val1)
00333 return self
00334 except struct.error as e:
00335 raise genpy.DeserializationError(e)
00336
00337 _struct_I = genpy.struct_I
00338 _struct_3I = struct.Struct("<3I")
00339 _struct_7d4fb = struct.Struct("<7d4fb")
00340 _struct_3d = struct.Struct("<3d")
00341 """autogenerated by genpy from tabletop_object_detector/TabletopSegmentationResponse.msg. Do not edit."""
00342 import sys
00343 python3 = True if sys.hexversion > 0x03000000 else False
00344 import genpy
00345 import struct
00346
00347 import arm_navigation_msgs.msg
00348 import tabletop_object_detector.msg
00349 import sensor_msgs.msg
00350 import geometry_msgs.msg
00351 import std_msgs.msg
00352
00353 class TabletopSegmentationResponse(genpy.Message):
00354 _md5sum = "1ece7d86360ba38c12673652ea654b18"
00355 _type = "tabletop_object_detector/TabletopSegmentationResponse"
00356 _has_header = False
00357 _full_text = """
00358
00359 Table table
00360
00361
00362 sensor_msgs/PointCloud[] clusters
00363
00364
00365 int32 NO_CLOUD_RECEIVED = 1
00366 int32 NO_TABLE = 2
00367 int32 OTHER_ERROR = 3
00368 int32 SUCCESS = 4
00369 int32 result
00370
00371
00372 ================================================================================
00373 MSG: tabletop_object_detector/Table
00374 # Informs that a planar table has been detected at a given location
00375
00376 # The pose gives you the transform that take you to the coordinate system
00377 # of the table, with the origin somewhere in the table plane and the
00378 # z axis normal to the plane
00379 geometry_msgs/PoseStamped pose
00380
00381 # These values give you the observed extents of the table, along x and y,
00382 # in the table's own coordinate system (above)
00383 # there is no guarantee that the origin of the table coordinate system is
00384 # inside the boundary defined by these values.
00385 float32 x_min
00386 float32 x_max
00387 float32 y_min
00388 float32 y_max
00389
00390 # There is no guarantee that the table does NOT extend further than these
00391 # values; this is just as far as we've observed it.
00392
00393
00394 # Newer table definition as triangle mesh of convex hull (relative to pose)
00395 arm_navigation_msgs/Shape convex_hull
00396
00397 ================================================================================
00398 MSG: geometry_msgs/PoseStamped
00399 # A Pose with reference coordinate frame and timestamp
00400 Header header
00401 Pose pose
00402
00403 ================================================================================
00404 MSG: std_msgs/Header
00405 # Standard metadata for higher-level stamped data types.
00406 # This is generally used to communicate timestamped data
00407 # in a particular coordinate frame.
00408 #
00409 # sequence ID: consecutively increasing ID
00410 uint32 seq
00411 #Two-integer timestamp that is expressed as:
00412 # * stamp.secs: seconds (stamp_secs) since epoch
00413 # * stamp.nsecs: nanoseconds since stamp_secs
00414 # time-handling sugar is provided by the client library
00415 time stamp
00416 #Frame this data is associated with
00417 # 0: no frame
00418 # 1: global frame
00419 string frame_id
00420
00421 ================================================================================
00422 MSG: geometry_msgs/Pose
00423 # A representation of pose in free space, composed of postion and orientation.
00424 Point position
00425 Quaternion orientation
00426
00427 ================================================================================
00428 MSG: geometry_msgs/Point
00429 # This contains the position of a point in free space
00430 float64 x
00431 float64 y
00432 float64 z
00433
00434 ================================================================================
00435 MSG: geometry_msgs/Quaternion
00436 # This represents an orientation in free space in quaternion form.
00437
00438 float64 x
00439 float64 y
00440 float64 z
00441 float64 w
00442
00443 ================================================================================
00444 MSG: arm_navigation_msgs/Shape
00445 byte SPHERE=0
00446 byte BOX=1
00447 byte CYLINDER=2
00448 byte MESH=3
00449
00450 byte type
00451
00452
00453 #### define sphere, box, cylinder ####
00454 # the origin of each shape is considered at the shape's center
00455
00456 # for sphere
00457 # radius := dimensions[0]
00458
00459 # for cylinder
00460 # radius := dimensions[0]
00461 # length := dimensions[1]
00462 # the length is along the Z axis
00463
00464 # for box
00465 # size_x := dimensions[0]
00466 # size_y := dimensions[1]
00467 # size_z := dimensions[2]
00468 float64[] dimensions
00469
00470
00471 #### define mesh ####
00472
00473 # list of triangles; triangle k is defined by tre vertices located
00474 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00475 int32[] triangles
00476 geometry_msgs/Point[] vertices
00477
00478 ================================================================================
00479 MSG: sensor_msgs/PointCloud
00480 # This message holds a collection of 3d points, plus optional additional
00481 # information about each point.
00482
00483 # Time of sensor data acquisition, coordinate frame ID.
00484 Header header
00485
00486 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00487 # in the frame given in the header.
00488 geometry_msgs/Point32[] points
00489
00490 # Each channel should have the same number of elements as points array,
00491 # and the data in each channel should correspond 1:1 with each point.
00492 # Channel names in common practice are listed in ChannelFloat32.msg.
00493 ChannelFloat32[] channels
00494
00495 ================================================================================
00496 MSG: geometry_msgs/Point32
00497 # This contains the position of a point in free space(with 32 bits of precision).
00498 # It is recommeded to use Point wherever possible instead of Point32.
00499 #
00500 # This recommendation is to promote interoperability.
00501 #
00502 # This message is designed to take up less space when sending
00503 # lots of points at once, as in the case of a PointCloud.
00504
00505 float32 x
00506 float32 y
00507 float32 z
00508 ================================================================================
00509 MSG: sensor_msgs/ChannelFloat32
00510 # This message is used by the PointCloud message to hold optional data
00511 # associated with each point in the cloud. The length of the values
00512 # array should be the same as the length of the points array in the
00513 # PointCloud, and each value should be associated with the corresponding
00514 # point.
00515
00516 # Channel names in existing practice include:
00517 # "u", "v" - row and column (respectively) in the left stereo image.
00518 # This is opposite to usual conventions but remains for
00519 # historical reasons. The newer PointCloud2 message has no
00520 # such problem.
00521 # "rgb" - For point clouds produced by color stereo cameras. uint8
00522 # (R,G,B) values packed into the least significant 24 bits,
00523 # in order.
00524 # "intensity" - laser or pixel intensity.
00525 # "distance"
00526
00527 # The channel name should give semantics of the channel (e.g.
00528 # "intensity" instead of "value").
00529 string name
00530
00531 # The values array should be 1-1 with the elements of the associated
00532 # PointCloud.
00533 float32[] values
00534
00535 """
00536 # Pseudo-constants
00537 NO_CLOUD_RECEIVED = 1
00538 NO_TABLE = 2
00539 OTHER_ERROR = 3
00540 SUCCESS = 4
00541
00542 __slots__ = ['table','clusters','result']
00543 _slot_types = ['tabletop_object_detector/Table','sensor_msgs/PointCloud[]','int32']
00544
00545 def __init__(self, *args, **kwds):
00546 """
00547 Constructor. Any message fields that are implicitly/explicitly
00548 set to None will be assigned a default value. The recommend
00549 use is keyword arguments as this is more robust to future message
00550 changes. You cannot mix in-order arguments and keyword arguments.
00551
00552 The available fields are:
00553 table,clusters,result
00554
00555 :param args: complete set of field values, in .msg order
00556 :param kwds: use keyword arguments corresponding to message field names
00557 to set specific fields.
00558 """
00559 if args or kwds:
00560 super(TabletopSegmentationResponse, self).__init__(*args, **kwds)
00561 #message fields cannot be None, assign default values for those that are
00562 if self.table is None:
00563 self.table = tabletop_object_detector.msg.Table()
00564 if self.clusters is None:
00565 self.clusters = []
00566 if self.result is None:
00567 self.result = 0
00568 else:
00569 self.table = tabletop_object_detector.msg.Table()
00570 self.clusters = []
00571 self.result = 0
00572
00573 def _get_types(self):
00574 """
00575 internal API method
00576 """
00577 return self._slot_types
00578
00579 def serialize(self, buff):
00580 """
00581 serialize message into buffer
00582 :param buff: buffer, ``StringIO``
00583 """
00584 try:
00585 _x = self
00586 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00587 _x = self.table.pose.header.frame_id
00588 length = len(_x)
00589 if python3 or type(_x) == unicode:
00590 _x = _x.encode('utf-8')
00591 length = len(_x)
00592 buff.write(struct.pack('<I%ss'%length, length, _x))
00593 _x = self
00594 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))
00595 length = len(self.table.convex_hull.dimensions)
00596 buff.write(_struct_I.pack(length))
00597 pattern = '<%sd'%length
00598 buff.write(struct.pack(pattern, *self.table.convex_hull.dimensions))
00599 length = len(self.table.convex_hull.triangles)
00600 buff.write(_struct_I.pack(length))
00601 pattern = '<%si'%length
00602 buff.write(struct.pack(pattern, *self.table.convex_hull.triangles))
00603 length = len(self.table.convex_hull.vertices)
00604 buff.write(_struct_I.pack(length))
00605 for val1 in self.table.convex_hull.vertices:
00606 _x = val1
00607 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00608 length = len(self.clusters)
00609 buff.write(_struct_I.pack(length))
00610 for val1 in self.clusters:
00611 _v1 = val1.header
00612 buff.write(_struct_I.pack(_v1.seq))
00613 _v2 = _v1.stamp
00614 _x = _v2
00615 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00616 _x = _v1.frame_id
00617 length = len(_x)
00618 if python3 or type(_x) == unicode:
00619 _x = _x.encode('utf-8')
00620 length = len(_x)
00621 buff.write(struct.pack('<I%ss'%length, length, _x))
00622 length = len(val1.points)
00623 buff.write(_struct_I.pack(length))
00624 for val2 in val1.points:
00625 _x = val2
00626 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00627 length = len(val1.channels)
00628 buff.write(_struct_I.pack(length))
00629 for val2 in val1.channels:
00630 _x = val2.name
00631 length = len(_x)
00632 if python3 or type(_x) == unicode:
00633 _x = _x.encode('utf-8')
00634 length = len(_x)
00635 buff.write(struct.pack('<I%ss'%length, length, _x))
00636 length = len(val2.values)
00637 buff.write(_struct_I.pack(length))
00638 pattern = '<%sf'%length
00639 buff.write(struct.pack(pattern, *val2.values))
00640 buff.write(_struct_i.pack(self.result))
00641 except struct.error as se: self._check_types(se)
00642 except TypeError as te: self._check_types(te)
00643
00644 def deserialize(self, str):
00645 """
00646 unpack serialized message in str into this message instance
00647 :param str: byte array of serialized message, ``str``
00648 """
00649 try:
00650 if self.table is None:
00651 self.table = tabletop_object_detector.msg.Table()
00652 if self.clusters is None:
00653 self.clusters = None
00654 end = 0
00655 _x = self
00656 start = end
00657 end += 12
00658 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00659 start = end
00660 end += 4
00661 (length,) = _struct_I.unpack(str[start:end])
00662 start = end
00663 end += length
00664 if python3:
00665 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00666 else:
00667 self.table.pose.header.frame_id = str[start:end]
00668 _x = self
00669 start = end
00670 end += 73
00671 (_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])
00672 start = end
00673 end += 4
00674 (length,) = _struct_I.unpack(str[start:end])
00675 pattern = '<%sd'%length
00676 start = end
00677 end += struct.calcsize(pattern)
00678 self.table.convex_hull.dimensions = struct.unpack(pattern, str[start:end])
00679 start = end
00680 end += 4
00681 (length,) = _struct_I.unpack(str[start:end])
00682 pattern = '<%si'%length
00683 start = end
00684 end += struct.calcsize(pattern)
00685 self.table.convex_hull.triangles = struct.unpack(pattern, str[start:end])
00686 start = end
00687 end += 4
00688 (length,) = _struct_I.unpack(str[start:end])
00689 self.table.convex_hull.vertices = []
00690 for i in range(0, length):
00691 val1 = geometry_msgs.msg.Point()
00692 _x = val1
00693 start = end
00694 end += 24
00695 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00696 self.table.convex_hull.vertices.append(val1)
00697 start = end
00698 end += 4
00699 (length,) = _struct_I.unpack(str[start:end])
00700 self.clusters = []
00701 for i in range(0, length):
00702 val1 = sensor_msgs.msg.PointCloud()
00703 _v3 = val1.header
00704 start = end
00705 end += 4
00706 (_v3.seq,) = _struct_I.unpack(str[start:end])
00707 _v4 = _v3.stamp
00708 _x = _v4
00709 start = end
00710 end += 8
00711 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00712 start = end
00713 end += 4
00714 (length,) = _struct_I.unpack(str[start:end])
00715 start = end
00716 end += length
00717 if python3:
00718 _v3.frame_id = str[start:end].decode('utf-8')
00719 else:
00720 _v3.frame_id = str[start:end]
00721 start = end
00722 end += 4
00723 (length,) = _struct_I.unpack(str[start:end])
00724 val1.points = []
00725 for i in range(0, length):
00726 val2 = geometry_msgs.msg.Point32()
00727 _x = val2
00728 start = end
00729 end += 12
00730 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00731 val1.points.append(val2)
00732 start = end
00733 end += 4
00734 (length,) = _struct_I.unpack(str[start:end])
00735 val1.channels = []
00736 for i in range(0, length):
00737 val2 = sensor_msgs.msg.ChannelFloat32()
00738 start = end
00739 end += 4
00740 (length,) = _struct_I.unpack(str[start:end])
00741 start = end
00742 end += length
00743 if python3:
00744 val2.name = str[start:end].decode('utf-8')
00745 else:
00746 val2.name = str[start:end]
00747 start = end
00748 end += 4
00749 (length,) = _struct_I.unpack(str[start:end])
00750 pattern = '<%sf'%length
00751 start = end
00752 end += struct.calcsize(pattern)
00753 val2.values = struct.unpack(pattern, str[start:end])
00754 val1.channels.append(val2)
00755 self.clusters.append(val1)
00756 start = end
00757 end += 4
00758 (self.result,) = _struct_i.unpack(str[start:end])
00759 return self
00760 except struct.error as e:
00761 raise genpy.DeserializationError(e) #most likely buffer underfill
00762
00763
00764 def serialize_numpy(self, buff, numpy):
00765 """
00766 serialize message with numpy array types into buffer
00767 :param buff: buffer, ``StringIO``
00768 :param numpy: numpy python module
00769 """
00770 try:
00771 _x = self
00772 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00773 _x = self.table.pose.header.frame_id
00774 length = len(_x)
00775 if python3 or type(_x) == unicode:
00776 _x = _x.encode('utf-8')
00777 length = len(_x)
00778 buff.write(struct.pack('<I%ss'%length, length, _x))
00779 _x = self
00780 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))
00781 length = len(self.table.convex_hull.dimensions)
00782 buff.write(_struct_I.pack(length))
00783 pattern = '<%sd'%length
00784 buff.write(self.table.convex_hull.dimensions.tostring())
00785 length = len(self.table.convex_hull.triangles)
00786 buff.write(_struct_I.pack(length))
00787 pattern = '<%si'%length
00788 buff.write(self.table.convex_hull.triangles.tostring())
00789 length = len(self.table.convex_hull.vertices)
00790 buff.write(_struct_I.pack(length))
00791 for val1 in self.table.convex_hull.vertices:
00792 _x = val1
00793 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00794 length = len(self.clusters)
00795 buff.write(_struct_I.pack(length))
00796 for val1 in self.clusters:
00797 _v5 = val1.header
00798 buff.write(_struct_I.pack(_v5.seq))
00799 _v6 = _v5.stamp
00800 _x = _v6
00801 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00802 _x = _v5.frame_id
00803 length = len(_x)
00804 if python3 or type(_x) == unicode:
00805 _x = _x.encode('utf-8')
00806 length = len(_x)
00807 buff.write(struct.pack('<I%ss'%length, length, _x))
00808 length = len(val1.points)
00809 buff.write(_struct_I.pack(length))
00810 for val2 in val1.points:
00811 _x = val2
00812 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00813 length = len(val1.channels)
00814 buff.write(_struct_I.pack(length))
00815 for val2 in val1.channels:
00816 _x = val2.name
00817 length = len(_x)
00818 if python3 or type(_x) == unicode:
00819 _x = _x.encode('utf-8')
00820 length = len(_x)
00821 buff.write(struct.pack('<I%ss'%length, length, _x))
00822 length = len(val2.values)
00823 buff.write(_struct_I.pack(length))
00824 pattern = '<%sf'%length
00825 buff.write(val2.values.tostring())
00826 buff.write(_struct_i.pack(self.result))
00827 except struct.error as se: self._check_types(se)
00828 except TypeError as te: self._check_types(te)
00829
00830 def deserialize_numpy(self, str, numpy):
00831 """
00832 unpack serialized message in str into this message instance using numpy for array types
00833 :param str: byte array of serialized message, ``str``
00834 :param numpy: numpy python module
00835 """
00836 try:
00837 if self.table is None:
00838 self.table = tabletop_object_detector.msg.Table()
00839 if self.clusters is None:
00840 self.clusters = None
00841 end = 0
00842 _x = self
00843 start = end
00844 end += 12
00845 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00846 start = end
00847 end += 4
00848 (length,) = _struct_I.unpack(str[start:end])
00849 start = end
00850 end += length
00851 if python3:
00852 self.table.pose.header.frame_id = str[start:end].decode('utf-8')
00853 else:
00854 self.table.pose.header.frame_id = str[start:end]
00855 _x = self
00856 start = end
00857 end += 73
00858 (_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])
00859 start = end
00860 end += 4
00861 (length,) = _struct_I.unpack(str[start:end])
00862 pattern = '<%sd'%length
00863 start = end
00864 end += struct.calcsize(pattern)
00865 self.table.convex_hull.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00866 start = end
00867 end += 4
00868 (length,) = _struct_I.unpack(str[start:end])
00869 pattern = '<%si'%length
00870 start = end
00871 end += struct.calcsize(pattern)
00872 self.table.convex_hull.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00873 start = end
00874 end += 4
00875 (length,) = _struct_I.unpack(str[start:end])
00876 self.table.convex_hull.vertices = []
00877 for i in range(0, length):
00878 val1 = geometry_msgs.msg.Point()
00879 _x = val1
00880 start = end
00881 end += 24
00882 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00883 self.table.convex_hull.vertices.append(val1)
00884 start = end
00885 end += 4
00886 (length,) = _struct_I.unpack(str[start:end])
00887 self.clusters = []
00888 for i in range(0, length):
00889 val1 = sensor_msgs.msg.PointCloud()
00890 _v7 = val1.header
00891 start = end
00892 end += 4
00893 (_v7.seq,) = _struct_I.unpack(str[start:end])
00894 _v8 = _v7.stamp
00895 _x = _v8
00896 start = end
00897 end += 8
00898 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00899 start = end
00900 end += 4
00901 (length,) = _struct_I.unpack(str[start:end])
00902 start = end
00903 end += length
00904 if python3:
00905 _v7.frame_id = str[start:end].decode('utf-8')
00906 else:
00907 _v7.frame_id = str[start:end]
00908 start = end
00909 end += 4
00910 (length,) = _struct_I.unpack(str[start:end])
00911 val1.points = []
00912 for i in range(0, length):
00913 val2 = geometry_msgs.msg.Point32()
00914 _x = val2
00915 start = end
00916 end += 12
00917 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00918 val1.points.append(val2)
00919 start = end
00920 end += 4
00921 (length,) = _struct_I.unpack(str[start:end])
00922 val1.channels = []
00923 for i in range(0, length):
00924 val2 = sensor_msgs.msg.ChannelFloat32()
00925 start = end
00926 end += 4
00927 (length,) = _struct_I.unpack(str[start:end])
00928 start = end
00929 end += length
00930 if python3:
00931 val2.name = str[start:end].decode('utf-8')
00932 else:
00933 val2.name = str[start:end]
00934 start = end
00935 end += 4
00936 (length,) = _struct_I.unpack(str[start:end])
00937 pattern = '<%sf'%length
00938 start = end
00939 end += struct.calcsize(pattern)
00940 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00941 val1.channels.append(val2)
00942 self.clusters.append(val1)
00943 start = end
00944 end += 4
00945 (self.result,) = _struct_i.unpack(str[start:end])
00946 return self
00947 except struct.error as e:
00948 raise genpy.DeserializationError(e) #most likely buffer underfill
00949
00950 _struct_I = genpy.struct_I
00951 _struct_7d4fb = struct.Struct("<7d4fb")
00952 _struct_2I = struct.Struct("<2I")
00953 _struct_i = struct.Struct("<i")
00954 _struct_3I = struct.Struct("<3I")
00955 _struct_3f = struct.Struct("<3f")
00956 _struct_3d = struct.Struct("<3d")
00957 class TabletopSegmentation(object):
00958 _type = 'tabletop_object_detector/TabletopSegmentation'
00959 _md5sum = 'f7ebff3d714e0788849f9ca334c83a5f'
00960 _request_class = TabletopSegmentationRequest
00961 _response_class = TabletopSegmentationResponse