00001 """autogenerated by genpy from iri_perception_msgs/object_pose_detectionGoal.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 std_msgs.msg
00008 import sensor_msgs.msg
00009
00010 class object_pose_detectionGoal(genpy.Message):
00011 _md5sum = "bb2dc0a4b5cc55bda6bb01845b7f0217"
00012 _type = "iri_perception_msgs/object_pose_detectionGoal"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015 #goal definition
00016 sensor_msgs/Image image
00017 sensor_msgs/PointCloud2 pcl
00018
00019 ================================================================================
00020 MSG: sensor_msgs/Image
00021 # This message contains an uncompressed image
00022 # (0, 0) is at top-left corner of image
00023 #
00024
00025 Header header # Header timestamp should be acquisition time of image
00026 # Header frame_id should be optical frame of camera
00027 # origin of frame should be optical center of cameara
00028 # +x should point to the right in the image
00029 # +y should point down in the image
00030 # +z should point into to plane of the image
00031 # If the frame_id here and the frame_id of the CameraInfo
00032 # message associated with the image conflict
00033 # the behavior is undefined
00034
00035 uint32 height # image height, that is, number of rows
00036 uint32 width # image width, that is, number of columns
00037
00038 # The legal values for encoding are in file src/image_encodings.cpp
00039 # If you want to standardize a new string format, join
00040 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00041
00042 string encoding # Encoding of pixels -- channel meaning, ordering, size
00043 # taken from the list of strings in src/image_encodings.cpp
00044
00045 uint8 is_bigendian # is this data bigendian?
00046 uint32 step # Full row length in bytes
00047 uint8[] data # actual matrix data, size is (step * rows)
00048
00049 ================================================================================
00050 MSG: std_msgs/Header
00051 # Standard metadata for higher-level stamped data types.
00052 # This is generally used to communicate timestamped data
00053 # in a particular coordinate frame.
00054 #
00055 # sequence ID: consecutively increasing ID
00056 uint32 seq
00057 #Two-integer timestamp that is expressed as:
00058 # * stamp.secs: seconds (stamp_secs) since epoch
00059 # * stamp.nsecs: nanoseconds since stamp_secs
00060 # time-handling sugar is provided by the client library
00061 time stamp
00062 #Frame this data is associated with
00063 # 0: no frame
00064 # 1: global frame
00065 string frame_id
00066
00067 ================================================================================
00068 MSG: sensor_msgs/PointCloud2
00069 # This message holds a collection of N-dimensional points, which may
00070 # contain additional information such as normals, intensity, etc. The
00071 # point data is stored as a binary blob, its layout described by the
00072 # contents of the "fields" array.
00073
00074 # The point cloud data may be organized 2d (image-like) or 1d
00075 # (unordered). Point clouds organized as 2d images may be produced by
00076 # camera depth sensors such as stereo or time-of-flight.
00077
00078 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00079 # points).
00080 Header header
00081
00082 # 2D structure of the point cloud. If the cloud is unordered, height is
00083 # 1 and width is the length of the point cloud.
00084 uint32 height
00085 uint32 width
00086
00087 # Describes the channels and their layout in the binary data blob.
00088 PointField[] fields
00089
00090 bool is_bigendian # Is this data bigendian?
00091 uint32 point_step # Length of a point in bytes
00092 uint32 row_step # Length of a row in bytes
00093 uint8[] data # Actual point data, size is (row_step*height)
00094
00095 bool is_dense # True if there are no invalid points
00096
00097 ================================================================================
00098 MSG: sensor_msgs/PointField
00099 # This message holds the description of one point entry in the
00100 # PointCloud2 message format.
00101 uint8 INT8 = 1
00102 uint8 UINT8 = 2
00103 uint8 INT16 = 3
00104 uint8 UINT16 = 4
00105 uint8 INT32 = 5
00106 uint8 UINT32 = 6
00107 uint8 FLOAT32 = 7
00108 uint8 FLOAT64 = 8
00109
00110 string name # Name of field
00111 uint32 offset # Offset from start of point struct
00112 uint8 datatype # Datatype enumeration, see above
00113 uint32 count # How many elements in the field
00114
00115 """
00116 __slots__ = ['image','pcl']
00117 _slot_types = ['sensor_msgs/Image','sensor_msgs/PointCloud2']
00118
00119 def __init__(self, *args, **kwds):
00120 """
00121 Constructor. Any message fields that are implicitly/explicitly
00122 set to None will be assigned a default value. The recommend
00123 use is keyword arguments as this is more robust to future message
00124 changes. You cannot mix in-order arguments and keyword arguments.
00125
00126 The available fields are:
00127 image,pcl
00128
00129 :param args: complete set of field values, in .msg order
00130 :param kwds: use keyword arguments corresponding to message field names
00131 to set specific fields.
00132 """
00133 if args or kwds:
00134 super(object_pose_detectionGoal, self).__init__(*args, **kwds)
00135
00136 if self.image is None:
00137 self.image = sensor_msgs.msg.Image()
00138 if self.pcl is None:
00139 self.pcl = sensor_msgs.msg.PointCloud2()
00140 else:
00141 self.image = sensor_msgs.msg.Image()
00142 self.pcl = sensor_msgs.msg.PointCloud2()
00143
00144 def _get_types(self):
00145 """
00146 internal API method
00147 """
00148 return self._slot_types
00149
00150 def serialize(self, buff):
00151 """
00152 serialize message into buffer
00153 :param buff: buffer, ``StringIO``
00154 """
00155 try:
00156 _x = self
00157 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00158 _x = self.image.header.frame_id
00159 length = len(_x)
00160 if python3 or type(_x) == unicode:
00161 _x = _x.encode('utf-8')
00162 length = len(_x)
00163 buff.write(struct.pack('<I%ss'%length, length, _x))
00164 _x = self
00165 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00166 _x = self.image.encoding
00167 length = len(_x)
00168 if python3 or type(_x) == unicode:
00169 _x = _x.encode('utf-8')
00170 length = len(_x)
00171 buff.write(struct.pack('<I%ss'%length, length, _x))
00172 _x = self
00173 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00174 _x = self.image.data
00175 length = len(_x)
00176
00177 if type(_x) in [list, tuple]:
00178 buff.write(struct.pack('<I%sB'%length, length, *_x))
00179 else:
00180 buff.write(struct.pack('<I%ss'%length, length, _x))
00181 _x = self
00182 buff.write(_struct_3I.pack(_x.pcl.header.seq, _x.pcl.header.stamp.secs, _x.pcl.header.stamp.nsecs))
00183 _x = self.pcl.header.frame_id
00184 length = len(_x)
00185 if python3 or type(_x) == unicode:
00186 _x = _x.encode('utf-8')
00187 length = len(_x)
00188 buff.write(struct.pack('<I%ss'%length, length, _x))
00189 _x = self
00190 buff.write(_struct_2I.pack(_x.pcl.height, _x.pcl.width))
00191 length = len(self.pcl.fields)
00192 buff.write(_struct_I.pack(length))
00193 for val1 in self.pcl.fields:
00194 _x = val1.name
00195 length = len(_x)
00196 if python3 or type(_x) == unicode:
00197 _x = _x.encode('utf-8')
00198 length = len(_x)
00199 buff.write(struct.pack('<I%ss'%length, length, _x))
00200 _x = val1
00201 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00202 _x = self
00203 buff.write(_struct_B2I.pack(_x.pcl.is_bigendian, _x.pcl.point_step, _x.pcl.row_step))
00204 _x = self.pcl.data
00205 length = len(_x)
00206
00207 if type(_x) in [list, tuple]:
00208 buff.write(struct.pack('<I%sB'%length, length, *_x))
00209 else:
00210 buff.write(struct.pack('<I%ss'%length, length, _x))
00211 buff.write(_struct_B.pack(self.pcl.is_dense))
00212 except struct.error as se: self._check_types(se)
00213 except TypeError as te: self._check_types(te)
00214
00215 def deserialize(self, str):
00216 """
00217 unpack serialized message in str into this message instance
00218 :param str: byte array of serialized message, ``str``
00219 """
00220 try:
00221 if self.image is None:
00222 self.image = sensor_msgs.msg.Image()
00223 if self.pcl is None:
00224 self.pcl = sensor_msgs.msg.PointCloud2()
00225 end = 0
00226 _x = self
00227 start = end
00228 end += 12
00229 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00230 start = end
00231 end += 4
00232 (length,) = _struct_I.unpack(str[start:end])
00233 start = end
00234 end += length
00235 if python3:
00236 self.image.header.frame_id = str[start:end].decode('utf-8')
00237 else:
00238 self.image.header.frame_id = str[start:end]
00239 _x = self
00240 start = end
00241 end += 8
00242 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00243 start = end
00244 end += 4
00245 (length,) = _struct_I.unpack(str[start:end])
00246 start = end
00247 end += length
00248 if python3:
00249 self.image.encoding = str[start:end].decode('utf-8')
00250 else:
00251 self.image.encoding = str[start:end]
00252 _x = self
00253 start = end
00254 end += 5
00255 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00256 start = end
00257 end += 4
00258 (length,) = _struct_I.unpack(str[start:end])
00259 start = end
00260 end += length
00261 if python3:
00262 self.image.data = str[start:end].decode('utf-8')
00263 else:
00264 self.image.data = str[start:end]
00265 _x = self
00266 start = end
00267 end += 12
00268 (_x.pcl.header.seq, _x.pcl.header.stamp.secs, _x.pcl.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00269 start = end
00270 end += 4
00271 (length,) = _struct_I.unpack(str[start:end])
00272 start = end
00273 end += length
00274 if python3:
00275 self.pcl.header.frame_id = str[start:end].decode('utf-8')
00276 else:
00277 self.pcl.header.frame_id = str[start:end]
00278 _x = self
00279 start = end
00280 end += 8
00281 (_x.pcl.height, _x.pcl.width,) = _struct_2I.unpack(str[start:end])
00282 start = end
00283 end += 4
00284 (length,) = _struct_I.unpack(str[start:end])
00285 self.pcl.fields = []
00286 for i in range(0, length):
00287 val1 = sensor_msgs.msg.PointField()
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 start = end
00292 end += length
00293 if python3:
00294 val1.name = str[start:end].decode('utf-8')
00295 else:
00296 val1.name = str[start:end]
00297 _x = val1
00298 start = end
00299 end += 9
00300 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00301 self.pcl.fields.append(val1)
00302 _x = self
00303 start = end
00304 end += 9
00305 (_x.pcl.is_bigendian, _x.pcl.point_step, _x.pcl.row_step,) = _struct_B2I.unpack(str[start:end])
00306 self.pcl.is_bigendian = bool(self.pcl.is_bigendian)
00307 start = end
00308 end += 4
00309 (length,) = _struct_I.unpack(str[start:end])
00310 start = end
00311 end += length
00312 if python3:
00313 self.pcl.data = str[start:end].decode('utf-8')
00314 else:
00315 self.pcl.data = str[start:end]
00316 start = end
00317 end += 1
00318 (self.pcl.is_dense,) = _struct_B.unpack(str[start:end])
00319 self.pcl.is_dense = bool(self.pcl.is_dense)
00320 return self
00321 except struct.error as e:
00322 raise genpy.DeserializationError(e)
00323
00324
00325 def serialize_numpy(self, buff, numpy):
00326 """
00327 serialize message with numpy array types into buffer
00328 :param buff: buffer, ``StringIO``
00329 :param numpy: numpy python module
00330 """
00331 try:
00332 _x = self
00333 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs))
00334 _x = self.image.header.frame_id
00335 length = len(_x)
00336 if python3 or type(_x) == unicode:
00337 _x = _x.encode('utf-8')
00338 length = len(_x)
00339 buff.write(struct.pack('<I%ss'%length, length, _x))
00340 _x = self
00341 buff.write(_struct_2I.pack(_x.image.height, _x.image.width))
00342 _x = self.image.encoding
00343 length = len(_x)
00344 if python3 or type(_x) == unicode:
00345 _x = _x.encode('utf-8')
00346 length = len(_x)
00347 buff.write(struct.pack('<I%ss'%length, length, _x))
00348 _x = self
00349 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step))
00350 _x = self.image.data
00351 length = len(_x)
00352
00353 if type(_x) in [list, tuple]:
00354 buff.write(struct.pack('<I%sB'%length, length, *_x))
00355 else:
00356 buff.write(struct.pack('<I%ss'%length, length, _x))
00357 _x = self
00358 buff.write(_struct_3I.pack(_x.pcl.header.seq, _x.pcl.header.stamp.secs, _x.pcl.header.stamp.nsecs))
00359 _x = self.pcl.header.frame_id
00360 length = len(_x)
00361 if python3 or type(_x) == unicode:
00362 _x = _x.encode('utf-8')
00363 length = len(_x)
00364 buff.write(struct.pack('<I%ss'%length, length, _x))
00365 _x = self
00366 buff.write(_struct_2I.pack(_x.pcl.height, _x.pcl.width))
00367 length = len(self.pcl.fields)
00368 buff.write(_struct_I.pack(length))
00369 for val1 in self.pcl.fields:
00370 _x = val1.name
00371 length = len(_x)
00372 if python3 or type(_x) == unicode:
00373 _x = _x.encode('utf-8')
00374 length = len(_x)
00375 buff.write(struct.pack('<I%ss'%length, length, _x))
00376 _x = val1
00377 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00378 _x = self
00379 buff.write(_struct_B2I.pack(_x.pcl.is_bigendian, _x.pcl.point_step, _x.pcl.row_step))
00380 _x = self.pcl.data
00381 length = len(_x)
00382
00383 if type(_x) in [list, tuple]:
00384 buff.write(struct.pack('<I%sB'%length, length, *_x))
00385 else:
00386 buff.write(struct.pack('<I%ss'%length, length, _x))
00387 buff.write(_struct_B.pack(self.pcl.is_dense))
00388 except struct.error as se: self._check_types(se)
00389 except TypeError as te: self._check_types(te)
00390
00391 def deserialize_numpy(self, str, numpy):
00392 """
00393 unpack serialized message in str into this message instance using numpy for array types
00394 :param str: byte array of serialized message, ``str``
00395 :param numpy: numpy python module
00396 """
00397 try:
00398 if self.image is None:
00399 self.image = sensor_msgs.msg.Image()
00400 if self.pcl is None:
00401 self.pcl = sensor_msgs.msg.PointCloud2()
00402 end = 0
00403 _x = self
00404 start = end
00405 end += 12
00406 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 start = end
00411 end += length
00412 if python3:
00413 self.image.header.frame_id = str[start:end].decode('utf-8')
00414 else:
00415 self.image.header.frame_id = str[start:end]
00416 _x = self
00417 start = end
00418 end += 8
00419 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end])
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 if python3:
00426 self.image.encoding = str[start:end].decode('utf-8')
00427 else:
00428 self.image.encoding = str[start:end]
00429 _x = self
00430 start = end
00431 end += 5
00432 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end])
00433 start = end
00434 end += 4
00435 (length,) = _struct_I.unpack(str[start:end])
00436 start = end
00437 end += length
00438 if python3:
00439 self.image.data = str[start:end].decode('utf-8')
00440 else:
00441 self.image.data = str[start:end]
00442 _x = self
00443 start = end
00444 end += 12
00445 (_x.pcl.header.seq, _x.pcl.header.stamp.secs, _x.pcl.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 start = end
00450 end += length
00451 if python3:
00452 self.pcl.header.frame_id = str[start:end].decode('utf-8')
00453 else:
00454 self.pcl.header.frame_id = str[start:end]
00455 _x = self
00456 start = end
00457 end += 8
00458 (_x.pcl.height, _x.pcl.width,) = _struct_2I.unpack(str[start:end])
00459 start = end
00460 end += 4
00461 (length,) = _struct_I.unpack(str[start:end])
00462 self.pcl.fields = []
00463 for i in range(0, length):
00464 val1 = sensor_msgs.msg.PointField()
00465 start = end
00466 end += 4
00467 (length,) = _struct_I.unpack(str[start:end])
00468 start = end
00469 end += length
00470 if python3:
00471 val1.name = str[start:end].decode('utf-8')
00472 else:
00473 val1.name = str[start:end]
00474 _x = val1
00475 start = end
00476 end += 9
00477 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00478 self.pcl.fields.append(val1)
00479 _x = self
00480 start = end
00481 end += 9
00482 (_x.pcl.is_bigendian, _x.pcl.point_step, _x.pcl.row_step,) = _struct_B2I.unpack(str[start:end])
00483 self.pcl.is_bigendian = bool(self.pcl.is_bigendian)
00484 start = end
00485 end += 4
00486 (length,) = _struct_I.unpack(str[start:end])
00487 start = end
00488 end += length
00489 if python3:
00490 self.pcl.data = str[start:end].decode('utf-8')
00491 else:
00492 self.pcl.data = str[start:end]
00493 start = end
00494 end += 1
00495 (self.pcl.is_dense,) = _struct_B.unpack(str[start:end])
00496 self.pcl.is_dense = bool(self.pcl.is_dense)
00497 return self
00498 except struct.error as e:
00499 raise genpy.DeserializationError(e)
00500
00501 _struct_I = genpy.struct_I
00502 _struct_IBI = struct.Struct("<IBI")
00503 _struct_B = struct.Struct("<B")
00504 _struct_BI = struct.Struct("<BI")
00505 _struct_3I = struct.Struct("<3I")
00506 _struct_B2I = struct.Struct("<B2I")
00507 _struct_2I = struct.Struct("<2I")