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


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:48:47