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


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Mon Oct 6 2014 11:45:29