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


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Thu Jan 2 2014 11:38:11