_FindContainerActionResult.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/FindContainerActionResult.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 object_manipulation_msgs.msg
00008 import actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013 
00014 class FindContainerActionResult(genpy.Message):
00015   _md5sum = "1c4fd4050a411725f1d3674520757b5d"
00016   _type = "object_manipulation_msgs/FindContainerActionResult"
00017   _has_header = True #flag to mark the presence of a Header object
00018   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019 
00020 Header header
00021 actionlib_msgs/GoalStatus status
00022 FindContainerResult result
00023 
00024 ================================================================================
00025 MSG: std_msgs/Header
00026 # Standard metadata for higher-level stamped data types.
00027 # This is generally used to communicate timestamped data 
00028 # in a particular coordinate frame.
00029 # 
00030 # sequence ID: consecutively increasing ID 
00031 uint32 seq
00032 #Two-integer timestamp that is expressed as:
00033 # * stamp.secs: seconds (stamp_secs) since epoch
00034 # * stamp.nsecs: nanoseconds since stamp_secs
00035 # time-handling sugar is provided by the client library
00036 time stamp
00037 #Frame this data is associated with
00038 # 0: no frame
00039 # 1: global frame
00040 string frame_id
00041 
00042 ================================================================================
00043 MSG: actionlib_msgs/GoalStatus
00044 GoalID goal_id
00045 uint8 status
00046 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00047 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00048 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00049                             #   and has since completed its execution (Terminal State)
00050 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00051 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00052                             #    to some failure (Terminal State)
00053 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00054                             #    because the goal was unattainable or invalid (Terminal State)
00055 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00056                             #    and has not yet completed execution
00057 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00058                             #    but the action server has not yet confirmed that the goal is canceled
00059 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00060                             #    and was successfully cancelled (Terminal State)
00061 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00062                             #    sent over the wire by an action server
00063 
00064 #Allow for the user to associate a string with GoalStatus for debugging
00065 string text
00066 
00067 
00068 ================================================================================
00069 MSG: actionlib_msgs/GoalID
00070 # The stamp should store the time at which this goal was requested.
00071 # It is used by an action server when it tries to preempt all
00072 # goals that were requested before a certain time
00073 time stamp
00074 
00075 # The id provides a way to associate feedback and
00076 # result message with specific goal requests. The id
00077 # specified must be unique.
00078 string id
00079 
00080 
00081 ================================================================================
00082 MSG: object_manipulation_msgs/FindContainerResult
00083 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00084 # refined pose and dimensions of bounding box for container
00085 geometry_msgs/PoseStamped box_pose
00086 geometry_msgs/Vector3     box_dims
00087 
00088 # cloud chunks of stuff in container, and container
00089 sensor_msgs/PointCloud2   contents
00090 sensor_msgs/PointCloud2   container
00091 sensor_msgs/PointCloud2[] clusters
00092 
00093 
00094 ================================================================================
00095 MSG: geometry_msgs/PoseStamped
00096 # A Pose with reference coordinate frame and timestamp
00097 Header header
00098 Pose pose
00099 
00100 ================================================================================
00101 MSG: geometry_msgs/Pose
00102 # A representation of pose in free space, composed of postion and orientation. 
00103 Point position
00104 Quaternion orientation
00105 
00106 ================================================================================
00107 MSG: geometry_msgs/Point
00108 # This contains the position of a point in free space
00109 float64 x
00110 float64 y
00111 float64 z
00112 
00113 ================================================================================
00114 MSG: geometry_msgs/Quaternion
00115 # This represents an orientation in free space in quaternion form.
00116 
00117 float64 x
00118 float64 y
00119 float64 z
00120 float64 w
00121 
00122 ================================================================================
00123 MSG: geometry_msgs/Vector3
00124 # This represents a vector in free space. 
00125 
00126 float64 x
00127 float64 y
00128 float64 z
00129 ================================================================================
00130 MSG: sensor_msgs/PointCloud2
00131 # This message holds a collection of N-dimensional points, which may
00132 # contain additional information such as normals, intensity, etc. The
00133 # point data is stored as a binary blob, its layout described by the
00134 # contents of the "fields" array.
00135 
00136 # The point cloud data may be organized 2d (image-like) or 1d
00137 # (unordered). Point clouds organized as 2d images may be produced by
00138 # camera depth sensors such as stereo or time-of-flight.
00139 
00140 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00141 # points).
00142 Header header
00143 
00144 # 2D structure of the point cloud. If the cloud is unordered, height is
00145 # 1 and width is the length of the point cloud.
00146 uint32 height
00147 uint32 width
00148 
00149 # Describes the channels and their layout in the binary data blob.
00150 PointField[] fields
00151 
00152 bool    is_bigendian # Is this data bigendian?
00153 uint32  point_step   # Length of a point in bytes
00154 uint32  row_step     # Length of a row in bytes
00155 uint8[] data         # Actual point data, size is (row_step*height)
00156 
00157 bool is_dense        # True if there are no invalid points
00158 
00159 ================================================================================
00160 MSG: sensor_msgs/PointField
00161 # This message holds the description of one point entry in the
00162 # PointCloud2 message format.
00163 uint8 INT8    = 1
00164 uint8 UINT8   = 2
00165 uint8 INT16   = 3
00166 uint8 UINT16  = 4
00167 uint8 INT32   = 5
00168 uint8 UINT32  = 6
00169 uint8 FLOAT32 = 7
00170 uint8 FLOAT64 = 8
00171 
00172 string name      # Name of field
00173 uint32 offset    # Offset from start of point struct
00174 uint8  datatype  # Datatype enumeration, see above
00175 uint32 count     # How many elements in the field
00176 
00177 """
00178   __slots__ = ['header','status','result']
00179   _slot_types = ['std_msgs/Header','actionlib_msgs/GoalStatus','object_manipulation_msgs/FindContainerResult']
00180 
00181   def __init__(self, *args, **kwds):
00182     """
00183     Constructor. Any message fields that are implicitly/explicitly
00184     set to None will be assigned a default value. The recommend
00185     use is keyword arguments as this is more robust to future message
00186     changes.  You cannot mix in-order arguments and keyword arguments.
00187 
00188     The available fields are:
00189        header,status,result
00190 
00191     :param args: complete set of field values, in .msg order
00192     :param kwds: use keyword arguments corresponding to message field names
00193     to set specific fields.
00194     """
00195     if args or kwds:
00196       super(FindContainerActionResult, self).__init__(*args, **kwds)
00197       #message fields cannot be None, assign default values for those that are
00198       if self.header is None:
00199         self.header = std_msgs.msg.Header()
00200       if self.status is None:
00201         self.status = actionlib_msgs.msg.GoalStatus()
00202       if self.result is None:
00203         self.result = object_manipulation_msgs.msg.FindContainerResult()
00204     else:
00205       self.header = std_msgs.msg.Header()
00206       self.status = actionlib_msgs.msg.GoalStatus()
00207       self.result = object_manipulation_msgs.msg.FindContainerResult()
00208 
00209   def _get_types(self):
00210     """
00211     internal API method
00212     """
00213     return self._slot_types
00214 
00215   def serialize(self, buff):
00216     """
00217     serialize message into buffer
00218     :param buff: buffer, ``StringIO``
00219     """
00220     try:
00221       _x = self
00222       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00223       _x = self.header.frame_id
00224       length = len(_x)
00225       if python3 or type(_x) == unicode:
00226         _x = _x.encode('utf-8')
00227         length = len(_x)
00228       buff.write(struct.pack('<I%ss'%length, length, _x))
00229       _x = self
00230       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00231       _x = self.status.goal_id.id
00232       length = len(_x)
00233       if python3 or type(_x) == unicode:
00234         _x = _x.encode('utf-8')
00235         length = len(_x)
00236       buff.write(struct.pack('<I%ss'%length, length, _x))
00237       buff.write(_struct_B.pack(self.status.status))
00238       _x = self.status.text
00239       length = len(_x)
00240       if python3 or type(_x) == unicode:
00241         _x = _x.encode('utf-8')
00242         length = len(_x)
00243       buff.write(struct.pack('<I%ss'%length, length, _x))
00244       _x = self
00245       buff.write(_struct_3I.pack(_x.result.box_pose.header.seq, _x.result.box_pose.header.stamp.secs, _x.result.box_pose.header.stamp.nsecs))
00246       _x = self.result.box_pose.header.frame_id
00247       length = len(_x)
00248       if python3 or type(_x) == unicode:
00249         _x = _x.encode('utf-8')
00250         length = len(_x)
00251       buff.write(struct.pack('<I%ss'%length, length, _x))
00252       _x = self
00253       buff.write(_struct_10d3I.pack(_x.result.box_pose.pose.position.x, _x.result.box_pose.pose.position.y, _x.result.box_pose.pose.position.z, _x.result.box_pose.pose.orientation.x, _x.result.box_pose.pose.orientation.y, _x.result.box_pose.pose.orientation.z, _x.result.box_pose.pose.orientation.w, _x.result.box_dims.x, _x.result.box_dims.y, _x.result.box_dims.z, _x.result.contents.header.seq, _x.result.contents.header.stamp.secs, _x.result.contents.header.stamp.nsecs))
00254       _x = self.result.contents.header.frame_id
00255       length = len(_x)
00256       if python3 or type(_x) == unicode:
00257         _x = _x.encode('utf-8')
00258         length = len(_x)
00259       buff.write(struct.pack('<I%ss'%length, length, _x))
00260       _x = self
00261       buff.write(_struct_2I.pack(_x.result.contents.height, _x.result.contents.width))
00262       length = len(self.result.contents.fields)
00263       buff.write(_struct_I.pack(length))
00264       for val1 in self.result.contents.fields:
00265         _x = val1.name
00266         length = len(_x)
00267         if python3 or type(_x) == unicode:
00268           _x = _x.encode('utf-8')
00269           length = len(_x)
00270         buff.write(struct.pack('<I%ss'%length, length, _x))
00271         _x = val1
00272         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00273       _x = self
00274       buff.write(_struct_B2I.pack(_x.result.contents.is_bigendian, _x.result.contents.point_step, _x.result.contents.row_step))
00275       _x = self.result.contents.data
00276       length = len(_x)
00277       # - if encoded as a list instead, serialize as bytes instead of string
00278       if type(_x) in [list, tuple]:
00279         buff.write(struct.pack('<I%sB'%length, length, *_x))
00280       else:
00281         buff.write(struct.pack('<I%ss'%length, length, _x))
00282       _x = self
00283       buff.write(_struct_B3I.pack(_x.result.contents.is_dense, _x.result.container.header.seq, _x.result.container.header.stamp.secs, _x.result.container.header.stamp.nsecs))
00284       _x = self.result.container.header.frame_id
00285       length = len(_x)
00286       if python3 or type(_x) == unicode:
00287         _x = _x.encode('utf-8')
00288         length = len(_x)
00289       buff.write(struct.pack('<I%ss'%length, length, _x))
00290       _x = self
00291       buff.write(_struct_2I.pack(_x.result.container.height, _x.result.container.width))
00292       length = len(self.result.container.fields)
00293       buff.write(_struct_I.pack(length))
00294       for val1 in self.result.container.fields:
00295         _x = val1.name
00296         length = len(_x)
00297         if python3 or type(_x) == unicode:
00298           _x = _x.encode('utf-8')
00299           length = len(_x)
00300         buff.write(struct.pack('<I%ss'%length, length, _x))
00301         _x = val1
00302         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00303       _x = self
00304       buff.write(_struct_B2I.pack(_x.result.container.is_bigendian, _x.result.container.point_step, _x.result.container.row_step))
00305       _x = self.result.container.data
00306       length = len(_x)
00307       # - if encoded as a list instead, serialize as bytes instead of string
00308       if type(_x) in [list, tuple]:
00309         buff.write(struct.pack('<I%sB'%length, length, *_x))
00310       else:
00311         buff.write(struct.pack('<I%ss'%length, length, _x))
00312       buff.write(_struct_B.pack(self.result.container.is_dense))
00313       length = len(self.result.clusters)
00314       buff.write(_struct_I.pack(length))
00315       for val1 in self.result.clusters:
00316         _v1 = val1.header
00317         buff.write(_struct_I.pack(_v1.seq))
00318         _v2 = _v1.stamp
00319         _x = _v2
00320         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00321         _x = _v1.frame_id
00322         length = len(_x)
00323         if python3 or type(_x) == unicode:
00324           _x = _x.encode('utf-8')
00325           length = len(_x)
00326         buff.write(struct.pack('<I%ss'%length, length, _x))
00327         _x = val1
00328         buff.write(_struct_2I.pack(_x.height, _x.width))
00329         length = len(val1.fields)
00330         buff.write(_struct_I.pack(length))
00331         for val2 in val1.fields:
00332           _x = val2.name
00333           length = len(_x)
00334           if python3 or type(_x) == unicode:
00335             _x = _x.encode('utf-8')
00336             length = len(_x)
00337           buff.write(struct.pack('<I%ss'%length, length, _x))
00338           _x = val2
00339           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00340         _x = val1
00341         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00342         _x = val1.data
00343         length = len(_x)
00344         # - if encoded as a list instead, serialize as bytes instead of string
00345         if type(_x) in [list, tuple]:
00346           buff.write(struct.pack('<I%sB'%length, length, *_x))
00347         else:
00348           buff.write(struct.pack('<I%ss'%length, length, _x))
00349         buff.write(_struct_B.pack(val1.is_dense))
00350     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00351     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00352 
00353   def deserialize(self, str):
00354     """
00355     unpack serialized message in str into this message instance
00356     :param str: byte array of serialized message, ``str``
00357     """
00358     try:
00359       if self.header is None:
00360         self.header = std_msgs.msg.Header()
00361       if self.status is None:
00362         self.status = actionlib_msgs.msg.GoalStatus()
00363       if self.result is None:
00364         self.result = object_manipulation_msgs.msg.FindContainerResult()
00365       end = 0
00366       _x = self
00367       start = end
00368       end += 12
00369       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00370       start = end
00371       end += 4
00372       (length,) = _struct_I.unpack(str[start:end])
00373       start = end
00374       end += length
00375       if python3:
00376         self.header.frame_id = str[start:end].decode('utf-8')
00377       else:
00378         self.header.frame_id = str[start:end]
00379       _x = self
00380       start = end
00381       end += 8
00382       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00383       start = end
00384       end += 4
00385       (length,) = _struct_I.unpack(str[start:end])
00386       start = end
00387       end += length
00388       if python3:
00389         self.status.goal_id.id = str[start:end].decode('utf-8')
00390       else:
00391         self.status.goal_id.id = str[start:end]
00392       start = end
00393       end += 1
00394       (self.status.status,) = _struct_B.unpack(str[start:end])
00395       start = end
00396       end += 4
00397       (length,) = _struct_I.unpack(str[start:end])
00398       start = end
00399       end += length
00400       if python3:
00401         self.status.text = str[start:end].decode('utf-8')
00402       else:
00403         self.status.text = str[start:end]
00404       _x = self
00405       start = end
00406       end += 12
00407       (_x.result.box_pose.header.seq, _x.result.box_pose.header.stamp.secs, _x.result.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00408       start = end
00409       end += 4
00410       (length,) = _struct_I.unpack(str[start:end])
00411       start = end
00412       end += length
00413       if python3:
00414         self.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
00415       else:
00416         self.result.box_pose.header.frame_id = str[start:end]
00417       _x = self
00418       start = end
00419       end += 92
00420       (_x.result.box_pose.pose.position.x, _x.result.box_pose.pose.position.y, _x.result.box_pose.pose.position.z, _x.result.box_pose.pose.orientation.x, _x.result.box_pose.pose.orientation.y, _x.result.box_pose.pose.orientation.z, _x.result.box_pose.pose.orientation.w, _x.result.box_dims.x, _x.result.box_dims.y, _x.result.box_dims.z, _x.result.contents.header.seq, _x.result.contents.header.stamp.secs, _x.result.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
00421       start = end
00422       end += 4
00423       (length,) = _struct_I.unpack(str[start:end])
00424       start = end
00425       end += length
00426       if python3:
00427         self.result.contents.header.frame_id = str[start:end].decode('utf-8')
00428       else:
00429         self.result.contents.header.frame_id = str[start:end]
00430       _x = self
00431       start = end
00432       end += 8
00433       (_x.result.contents.height, _x.result.contents.width,) = _struct_2I.unpack(str[start:end])
00434       start = end
00435       end += 4
00436       (length,) = _struct_I.unpack(str[start:end])
00437       self.result.contents.fields = []
00438       for i in range(0, length):
00439         val1 = sensor_msgs.msg.PointField()
00440         start = end
00441         end += 4
00442         (length,) = _struct_I.unpack(str[start:end])
00443         start = end
00444         end += length
00445         if python3:
00446           val1.name = str[start:end].decode('utf-8')
00447         else:
00448           val1.name = str[start:end]
00449         _x = val1
00450         start = end
00451         end += 9
00452         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00453         self.result.contents.fields.append(val1)
00454       _x = self
00455       start = end
00456       end += 9
00457       (_x.result.contents.is_bigendian, _x.result.contents.point_step, _x.result.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00458       self.result.contents.is_bigendian = bool(self.result.contents.is_bigendian)
00459       start = end
00460       end += 4
00461       (length,) = _struct_I.unpack(str[start:end])
00462       start = end
00463       end += length
00464       self.result.contents.data = str[start:end]
00465       _x = self
00466       start = end
00467       end += 13
00468       (_x.result.contents.is_dense, _x.result.container.header.seq, _x.result.container.header.stamp.secs, _x.result.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00469       self.result.contents.is_dense = bool(self.result.contents.is_dense)
00470       start = end
00471       end += 4
00472       (length,) = _struct_I.unpack(str[start:end])
00473       start = end
00474       end += length
00475       if python3:
00476         self.result.container.header.frame_id = str[start:end].decode('utf-8')
00477       else:
00478         self.result.container.header.frame_id = str[start:end]
00479       _x = self
00480       start = end
00481       end += 8
00482       (_x.result.container.height, _x.result.container.width,) = _struct_2I.unpack(str[start:end])
00483       start = end
00484       end += 4
00485       (length,) = _struct_I.unpack(str[start:end])
00486       self.result.container.fields = []
00487       for i in range(0, length):
00488         val1 = sensor_msgs.msg.PointField()
00489         start = end
00490         end += 4
00491         (length,) = _struct_I.unpack(str[start:end])
00492         start = end
00493         end += length
00494         if python3:
00495           val1.name = str[start:end].decode('utf-8')
00496         else:
00497           val1.name = str[start:end]
00498         _x = val1
00499         start = end
00500         end += 9
00501         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00502         self.result.container.fields.append(val1)
00503       _x = self
00504       start = end
00505       end += 9
00506       (_x.result.container.is_bigendian, _x.result.container.point_step, _x.result.container.row_step,) = _struct_B2I.unpack(str[start:end])
00507       self.result.container.is_bigendian = bool(self.result.container.is_bigendian)
00508       start = end
00509       end += 4
00510       (length,) = _struct_I.unpack(str[start:end])
00511       start = end
00512       end += length
00513       self.result.container.data = str[start:end]
00514       start = end
00515       end += 1
00516       (self.result.container.is_dense,) = _struct_B.unpack(str[start:end])
00517       self.result.container.is_dense = bool(self.result.container.is_dense)
00518       start = end
00519       end += 4
00520       (length,) = _struct_I.unpack(str[start:end])
00521       self.result.clusters = []
00522       for i in range(0, length):
00523         val1 = sensor_msgs.msg.PointCloud2()
00524         _v3 = val1.header
00525         start = end
00526         end += 4
00527         (_v3.seq,) = _struct_I.unpack(str[start:end])
00528         _v4 = _v3.stamp
00529         _x = _v4
00530         start = end
00531         end += 8
00532         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00533         start = end
00534         end += 4
00535         (length,) = _struct_I.unpack(str[start:end])
00536         start = end
00537         end += length
00538         if python3:
00539           _v3.frame_id = str[start:end].decode('utf-8')
00540         else:
00541           _v3.frame_id = str[start:end]
00542         _x = val1
00543         start = end
00544         end += 8
00545         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00546         start = end
00547         end += 4
00548         (length,) = _struct_I.unpack(str[start:end])
00549         val1.fields = []
00550         for i in range(0, length):
00551           val2 = sensor_msgs.msg.PointField()
00552           start = end
00553           end += 4
00554           (length,) = _struct_I.unpack(str[start:end])
00555           start = end
00556           end += length
00557           if python3:
00558             val2.name = str[start:end].decode('utf-8')
00559           else:
00560             val2.name = str[start:end]
00561           _x = val2
00562           start = end
00563           end += 9
00564           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00565           val1.fields.append(val2)
00566         _x = val1
00567         start = end
00568         end += 9
00569         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00570         val1.is_bigendian = bool(val1.is_bigendian)
00571         start = end
00572         end += 4
00573         (length,) = _struct_I.unpack(str[start:end])
00574         start = end
00575         end += length
00576         val1.data = str[start:end]
00577         start = end
00578         end += 1
00579         (val1.is_dense,) = _struct_B.unpack(str[start:end])
00580         val1.is_dense = bool(val1.is_dense)
00581         self.result.clusters.append(val1)
00582       return self
00583     except struct.error as e:
00584       raise genpy.DeserializationError(e) #most likely buffer underfill
00585 
00586 
00587   def serialize_numpy(self, buff, numpy):
00588     """
00589     serialize message with numpy array types into buffer
00590     :param buff: buffer, ``StringIO``
00591     :param numpy: numpy python module
00592     """
00593     try:
00594       _x = self
00595       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00596       _x = self.header.frame_id
00597       length = len(_x)
00598       if python3 or type(_x) == unicode:
00599         _x = _x.encode('utf-8')
00600         length = len(_x)
00601       buff.write(struct.pack('<I%ss'%length, length, _x))
00602       _x = self
00603       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00604       _x = self.status.goal_id.id
00605       length = len(_x)
00606       if python3 or type(_x) == unicode:
00607         _x = _x.encode('utf-8')
00608         length = len(_x)
00609       buff.write(struct.pack('<I%ss'%length, length, _x))
00610       buff.write(_struct_B.pack(self.status.status))
00611       _x = self.status.text
00612       length = len(_x)
00613       if python3 or type(_x) == unicode:
00614         _x = _x.encode('utf-8')
00615         length = len(_x)
00616       buff.write(struct.pack('<I%ss'%length, length, _x))
00617       _x = self
00618       buff.write(_struct_3I.pack(_x.result.box_pose.header.seq, _x.result.box_pose.header.stamp.secs, _x.result.box_pose.header.stamp.nsecs))
00619       _x = self.result.box_pose.header.frame_id
00620       length = len(_x)
00621       if python3 or type(_x) == unicode:
00622         _x = _x.encode('utf-8')
00623         length = len(_x)
00624       buff.write(struct.pack('<I%ss'%length, length, _x))
00625       _x = self
00626       buff.write(_struct_10d3I.pack(_x.result.box_pose.pose.position.x, _x.result.box_pose.pose.position.y, _x.result.box_pose.pose.position.z, _x.result.box_pose.pose.orientation.x, _x.result.box_pose.pose.orientation.y, _x.result.box_pose.pose.orientation.z, _x.result.box_pose.pose.orientation.w, _x.result.box_dims.x, _x.result.box_dims.y, _x.result.box_dims.z, _x.result.contents.header.seq, _x.result.contents.header.stamp.secs, _x.result.contents.header.stamp.nsecs))
00627       _x = self.result.contents.header.frame_id
00628       length = len(_x)
00629       if python3 or type(_x) == unicode:
00630         _x = _x.encode('utf-8')
00631         length = len(_x)
00632       buff.write(struct.pack('<I%ss'%length, length, _x))
00633       _x = self
00634       buff.write(_struct_2I.pack(_x.result.contents.height, _x.result.contents.width))
00635       length = len(self.result.contents.fields)
00636       buff.write(_struct_I.pack(length))
00637       for val1 in self.result.contents.fields:
00638         _x = val1.name
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         _x = val1
00645         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00646       _x = self
00647       buff.write(_struct_B2I.pack(_x.result.contents.is_bigendian, _x.result.contents.point_step, _x.result.contents.row_step))
00648       _x = self.result.contents.data
00649       length = len(_x)
00650       # - if encoded as a list instead, serialize as bytes instead of string
00651       if type(_x) in [list, tuple]:
00652         buff.write(struct.pack('<I%sB'%length, length, *_x))
00653       else:
00654         buff.write(struct.pack('<I%ss'%length, length, _x))
00655       _x = self
00656       buff.write(_struct_B3I.pack(_x.result.contents.is_dense, _x.result.container.header.seq, _x.result.container.header.stamp.secs, _x.result.container.header.stamp.nsecs))
00657       _x = self.result.container.header.frame_id
00658       length = len(_x)
00659       if python3 or type(_x) == unicode:
00660         _x = _x.encode('utf-8')
00661         length = len(_x)
00662       buff.write(struct.pack('<I%ss'%length, length, _x))
00663       _x = self
00664       buff.write(_struct_2I.pack(_x.result.container.height, _x.result.container.width))
00665       length = len(self.result.container.fields)
00666       buff.write(_struct_I.pack(length))
00667       for val1 in self.result.container.fields:
00668         _x = val1.name
00669         length = len(_x)
00670         if python3 or type(_x) == unicode:
00671           _x = _x.encode('utf-8')
00672           length = len(_x)
00673         buff.write(struct.pack('<I%ss'%length, length, _x))
00674         _x = val1
00675         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00676       _x = self
00677       buff.write(_struct_B2I.pack(_x.result.container.is_bigendian, _x.result.container.point_step, _x.result.container.row_step))
00678       _x = self.result.container.data
00679       length = len(_x)
00680       # - if encoded as a list instead, serialize as bytes instead of string
00681       if type(_x) in [list, tuple]:
00682         buff.write(struct.pack('<I%sB'%length, length, *_x))
00683       else:
00684         buff.write(struct.pack('<I%ss'%length, length, _x))
00685       buff.write(_struct_B.pack(self.result.container.is_dense))
00686       length = len(self.result.clusters)
00687       buff.write(_struct_I.pack(length))
00688       for val1 in self.result.clusters:
00689         _v5 = val1.header
00690         buff.write(_struct_I.pack(_v5.seq))
00691         _v6 = _v5.stamp
00692         _x = _v6
00693         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00694         _x = _v5.frame_id
00695         length = len(_x)
00696         if python3 or type(_x) == unicode:
00697           _x = _x.encode('utf-8')
00698           length = len(_x)
00699         buff.write(struct.pack('<I%ss'%length, length, _x))
00700         _x = val1
00701         buff.write(_struct_2I.pack(_x.height, _x.width))
00702         length = len(val1.fields)
00703         buff.write(_struct_I.pack(length))
00704         for val2 in val1.fields:
00705           _x = val2.name
00706           length = len(_x)
00707           if python3 or type(_x) == unicode:
00708             _x = _x.encode('utf-8')
00709             length = len(_x)
00710           buff.write(struct.pack('<I%ss'%length, length, _x))
00711           _x = val2
00712           buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00713         _x = val1
00714         buff.write(_struct_B2I.pack(_x.is_bigendian, _x.point_step, _x.row_step))
00715         _x = val1.data
00716         length = len(_x)
00717         # - if encoded as a list instead, serialize as bytes instead of string
00718         if type(_x) in [list, tuple]:
00719           buff.write(struct.pack('<I%sB'%length, length, *_x))
00720         else:
00721           buff.write(struct.pack('<I%ss'%length, length, _x))
00722         buff.write(_struct_B.pack(val1.is_dense))
00723     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00724     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00725 
00726   def deserialize_numpy(self, str, numpy):
00727     """
00728     unpack serialized message in str into this message instance using numpy for array types
00729     :param str: byte array of serialized message, ``str``
00730     :param numpy: numpy python module
00731     """
00732     try:
00733       if self.header is None:
00734         self.header = std_msgs.msg.Header()
00735       if self.status is None:
00736         self.status = actionlib_msgs.msg.GoalStatus()
00737       if self.result is None:
00738         self.result = object_manipulation_msgs.msg.FindContainerResult()
00739       end = 0
00740       _x = self
00741       start = end
00742       end += 12
00743       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00744       start = end
00745       end += 4
00746       (length,) = _struct_I.unpack(str[start:end])
00747       start = end
00748       end += length
00749       if python3:
00750         self.header.frame_id = str[start:end].decode('utf-8')
00751       else:
00752         self.header.frame_id = str[start:end]
00753       _x = self
00754       start = end
00755       end += 8
00756       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00757       start = end
00758       end += 4
00759       (length,) = _struct_I.unpack(str[start:end])
00760       start = end
00761       end += length
00762       if python3:
00763         self.status.goal_id.id = str[start:end].decode('utf-8')
00764       else:
00765         self.status.goal_id.id = str[start:end]
00766       start = end
00767       end += 1
00768       (self.status.status,) = _struct_B.unpack(str[start:end])
00769       start = end
00770       end += 4
00771       (length,) = _struct_I.unpack(str[start:end])
00772       start = end
00773       end += length
00774       if python3:
00775         self.status.text = str[start:end].decode('utf-8')
00776       else:
00777         self.status.text = str[start:end]
00778       _x = self
00779       start = end
00780       end += 12
00781       (_x.result.box_pose.header.seq, _x.result.box_pose.header.stamp.secs, _x.result.box_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00782       start = end
00783       end += 4
00784       (length,) = _struct_I.unpack(str[start:end])
00785       start = end
00786       end += length
00787       if python3:
00788         self.result.box_pose.header.frame_id = str[start:end].decode('utf-8')
00789       else:
00790         self.result.box_pose.header.frame_id = str[start:end]
00791       _x = self
00792       start = end
00793       end += 92
00794       (_x.result.box_pose.pose.position.x, _x.result.box_pose.pose.position.y, _x.result.box_pose.pose.position.z, _x.result.box_pose.pose.orientation.x, _x.result.box_pose.pose.orientation.y, _x.result.box_pose.pose.orientation.z, _x.result.box_pose.pose.orientation.w, _x.result.box_dims.x, _x.result.box_dims.y, _x.result.box_dims.z, _x.result.contents.header.seq, _x.result.contents.header.stamp.secs, _x.result.contents.header.stamp.nsecs,) = _struct_10d3I.unpack(str[start:end])
00795       start = end
00796       end += 4
00797       (length,) = _struct_I.unpack(str[start:end])
00798       start = end
00799       end += length
00800       if python3:
00801         self.result.contents.header.frame_id = str[start:end].decode('utf-8')
00802       else:
00803         self.result.contents.header.frame_id = str[start:end]
00804       _x = self
00805       start = end
00806       end += 8
00807       (_x.result.contents.height, _x.result.contents.width,) = _struct_2I.unpack(str[start:end])
00808       start = end
00809       end += 4
00810       (length,) = _struct_I.unpack(str[start:end])
00811       self.result.contents.fields = []
00812       for i in range(0, length):
00813         val1 = sensor_msgs.msg.PointField()
00814         start = end
00815         end += 4
00816         (length,) = _struct_I.unpack(str[start:end])
00817         start = end
00818         end += length
00819         if python3:
00820           val1.name = str[start:end].decode('utf-8')
00821         else:
00822           val1.name = str[start:end]
00823         _x = val1
00824         start = end
00825         end += 9
00826         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00827         self.result.contents.fields.append(val1)
00828       _x = self
00829       start = end
00830       end += 9
00831       (_x.result.contents.is_bigendian, _x.result.contents.point_step, _x.result.contents.row_step,) = _struct_B2I.unpack(str[start:end])
00832       self.result.contents.is_bigendian = bool(self.result.contents.is_bigendian)
00833       start = end
00834       end += 4
00835       (length,) = _struct_I.unpack(str[start:end])
00836       start = end
00837       end += length
00838       self.result.contents.data = str[start:end]
00839       _x = self
00840       start = end
00841       end += 13
00842       (_x.result.contents.is_dense, _x.result.container.header.seq, _x.result.container.header.stamp.secs, _x.result.container.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00843       self.result.contents.is_dense = bool(self.result.contents.is_dense)
00844       start = end
00845       end += 4
00846       (length,) = _struct_I.unpack(str[start:end])
00847       start = end
00848       end += length
00849       if python3:
00850         self.result.container.header.frame_id = str[start:end].decode('utf-8')
00851       else:
00852         self.result.container.header.frame_id = str[start:end]
00853       _x = self
00854       start = end
00855       end += 8
00856       (_x.result.container.height, _x.result.container.width,) = _struct_2I.unpack(str[start:end])
00857       start = end
00858       end += 4
00859       (length,) = _struct_I.unpack(str[start:end])
00860       self.result.container.fields = []
00861       for i in range(0, length):
00862         val1 = sensor_msgs.msg.PointField()
00863         start = end
00864         end += 4
00865         (length,) = _struct_I.unpack(str[start:end])
00866         start = end
00867         end += length
00868         if python3:
00869           val1.name = str[start:end].decode('utf-8')
00870         else:
00871           val1.name = str[start:end]
00872         _x = val1
00873         start = end
00874         end += 9
00875         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00876         self.result.container.fields.append(val1)
00877       _x = self
00878       start = end
00879       end += 9
00880       (_x.result.container.is_bigendian, _x.result.container.point_step, _x.result.container.row_step,) = _struct_B2I.unpack(str[start:end])
00881       self.result.container.is_bigendian = bool(self.result.container.is_bigendian)
00882       start = end
00883       end += 4
00884       (length,) = _struct_I.unpack(str[start:end])
00885       start = end
00886       end += length
00887       self.result.container.data = str[start:end]
00888       start = end
00889       end += 1
00890       (self.result.container.is_dense,) = _struct_B.unpack(str[start:end])
00891       self.result.container.is_dense = bool(self.result.container.is_dense)
00892       start = end
00893       end += 4
00894       (length,) = _struct_I.unpack(str[start:end])
00895       self.result.clusters = []
00896       for i in range(0, length):
00897         val1 = sensor_msgs.msg.PointCloud2()
00898         _v7 = val1.header
00899         start = end
00900         end += 4
00901         (_v7.seq,) = _struct_I.unpack(str[start:end])
00902         _v8 = _v7.stamp
00903         _x = _v8
00904         start = end
00905         end += 8
00906         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00907         start = end
00908         end += 4
00909         (length,) = _struct_I.unpack(str[start:end])
00910         start = end
00911         end += length
00912         if python3:
00913           _v7.frame_id = str[start:end].decode('utf-8')
00914         else:
00915           _v7.frame_id = str[start:end]
00916         _x = val1
00917         start = end
00918         end += 8
00919         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00920         start = end
00921         end += 4
00922         (length,) = _struct_I.unpack(str[start:end])
00923         val1.fields = []
00924         for i in range(0, length):
00925           val2 = sensor_msgs.msg.PointField()
00926           start = end
00927           end += 4
00928           (length,) = _struct_I.unpack(str[start:end])
00929           start = end
00930           end += length
00931           if python3:
00932             val2.name = str[start:end].decode('utf-8')
00933           else:
00934             val2.name = str[start:end]
00935           _x = val2
00936           start = end
00937           end += 9
00938           (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00939           val1.fields.append(val2)
00940         _x = val1
00941         start = end
00942         end += 9
00943         (_x.is_bigendian, _x.point_step, _x.row_step,) = _struct_B2I.unpack(str[start:end])
00944         val1.is_bigendian = bool(val1.is_bigendian)
00945         start = end
00946         end += 4
00947         (length,) = _struct_I.unpack(str[start:end])
00948         start = end
00949         end += length
00950         val1.data = str[start:end]
00951         start = end
00952         end += 1
00953         (val1.is_dense,) = _struct_B.unpack(str[start:end])
00954         val1.is_dense = bool(val1.is_dense)
00955         self.result.clusters.append(val1)
00956       return self
00957     except struct.error as e:
00958       raise genpy.DeserializationError(e) #most likely buffer underfill
00959 
00960 _struct_I = genpy.struct_I
00961 _struct_IBI = struct.Struct("<IBI")
00962 _struct_B = struct.Struct("<B")
00963 _struct_10d3I = struct.Struct("<10d3I")
00964 _struct_3I = struct.Struct("<3I")
00965 _struct_B3I = struct.Struct("<B3I")
00966 _struct_B2I = struct.Struct("<B2I")
00967 _struct_2I = struct.Struct("<2I")


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 02:58:11