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