00001 """autogenerated by genpy from zyonz_msgs/GetProbingStepsRequest.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 GetProbingStepsRequest(genpy.Message):
00011 _md5sum = "d8288ab03c94033ddae07988baace1f7"
00012 _type = "zyonz_msgs/GetProbingStepsRequest"
00013 _has_header = False
00014 _full_text = """
00015 sensor_msgs/PointCloud2 point_cloud
00016
00017 ================================================================================
00018 MSG: sensor_msgs/PointCloud2
00019 # This message holds a collection of N-dimensional points, which may
00020 # contain additional information such as normals, intensity, etc. The
00021 # point data is stored as a binary blob, its layout described by the
00022 # contents of the "fields" array.
00023
00024 # The point cloud data may be organized 2d (image-like) or 1d
00025 # (unordered). Point clouds organized as 2d images may be produced by
00026 # camera depth sensors such as stereo or time-of-flight.
00027
00028 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00029 # points).
00030 Header header
00031
00032 # 2D structure of the point cloud. If the cloud is unordered, height is
00033 # 1 and width is the length of the point cloud.
00034 uint32 height
00035 uint32 width
00036
00037 # Describes the channels and their layout in the binary data blob.
00038 PointField[] fields
00039
00040 bool is_bigendian # Is this data bigendian?
00041 uint32 point_step # Length of a point in bytes
00042 uint32 row_step # Length of a row in bytes
00043 uint8[] data # Actual point data, size is (row_step*height)
00044
00045 bool is_dense # True if there are no invalid points
00046
00047 ================================================================================
00048 MSG: std_msgs/Header
00049 # Standard metadata for higher-level stamped data types.
00050 # This is generally used to communicate timestamped data
00051 # in a particular coordinate frame.
00052 #
00053 # sequence ID: consecutively increasing ID
00054 uint32 seq
00055 #Two-integer timestamp that is expressed as:
00056 # * stamp.secs: seconds (stamp_secs) since epoch
00057 # * stamp.nsecs: nanoseconds since stamp_secs
00058 # time-handling sugar is provided by the client library
00059 time stamp
00060 #Frame this data is associated with
00061 # 0: no frame
00062 # 1: global frame
00063 string frame_id
00064
00065 ================================================================================
00066 MSG: sensor_msgs/PointField
00067 # This message holds the description of one point entry in the
00068 # PointCloud2 message format.
00069 uint8 INT8 = 1
00070 uint8 UINT8 = 2
00071 uint8 INT16 = 3
00072 uint8 UINT16 = 4
00073 uint8 INT32 = 5
00074 uint8 UINT32 = 6
00075 uint8 FLOAT32 = 7
00076 uint8 FLOAT64 = 8
00077
00078 string name # Name of field
00079 uint32 offset # Offset from start of point struct
00080 uint8 datatype # Datatype enumeration, see above
00081 uint32 count # How many elements in the field
00082
00083 """
00084 __slots__ = ['point_cloud']
00085 _slot_types = ['sensor_msgs/PointCloud2']
00086
00087 def __init__(self, *args, **kwds):
00088 """
00089 Constructor. Any message fields that are implicitly/explicitly
00090 set to None will be assigned a default value. The recommend
00091 use is keyword arguments as this is more robust to future message
00092 changes. You cannot mix in-order arguments and keyword arguments.
00093
00094 The available fields are:
00095 point_cloud
00096
00097 :param args: complete set of field values, in .msg order
00098 :param kwds: use keyword arguments corresponding to message field names
00099 to set specific fields.
00100 """
00101 if args or kwds:
00102 super(GetProbingStepsRequest, self).__init__(*args, **kwds)
00103
00104 if self.point_cloud is None:
00105 self.point_cloud = sensor_msgs.msg.PointCloud2()
00106 else:
00107 self.point_cloud = sensor_msgs.msg.PointCloud2()
00108
00109 def _get_types(self):
00110 """
00111 internal API method
00112 """
00113 return self._slot_types
00114
00115 def serialize(self, buff):
00116 """
00117 serialize message into buffer
00118 :param buff: buffer, ``StringIO``
00119 """
00120 try:
00121 _x = self
00122 buff.write(_struct_3I.pack(_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
00123 _x = self.point_cloud.header.frame_id
00124 length = len(_x)
00125 if python3 or type(_x) == unicode:
00126 _x = _x.encode('utf-8')
00127 length = len(_x)
00128 buff.write(struct.pack('<I%ss'%length, length, _x))
00129 _x = self
00130 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
00131 length = len(self.point_cloud.fields)
00132 buff.write(_struct_I.pack(length))
00133 for val1 in self.point_cloud.fields:
00134 _x = val1.name
00135 length = len(_x)
00136 if python3 or type(_x) == unicode:
00137 _x = _x.encode('utf-8')
00138 length = len(_x)
00139 buff.write(struct.pack('<I%ss'%length, length, _x))
00140 _x = val1
00141 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00142 _x = self
00143 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
00144 _x = self.point_cloud.data
00145 length = len(_x)
00146
00147 if type(_x) in [list, tuple]:
00148 buff.write(struct.pack('<I%sB'%length, length, *_x))
00149 else:
00150 buff.write(struct.pack('<I%ss'%length, length, _x))
00151 buff.write(_struct_B.pack(self.point_cloud.is_dense))
00152 except struct.error as se: self._check_types(se)
00153 except TypeError as te: self._check_types(te)
00154
00155 def deserialize(self, str):
00156 """
00157 unpack serialized message in str into this message instance
00158 :param str: byte array of serialized message, ``str``
00159 """
00160 try:
00161 if self.point_cloud is None:
00162 self.point_cloud = sensor_msgs.msg.PointCloud2()
00163 end = 0
00164 _x = self
00165 start = end
00166 end += 12
00167 (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00168 start = end
00169 end += 4
00170 (length,) = _struct_I.unpack(str[start:end])
00171 start = end
00172 end += length
00173 if python3:
00174 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
00175 else:
00176 self.point_cloud.header.frame_id = str[start:end]
00177 _x = self
00178 start = end
00179 end += 8
00180 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
00181 start = end
00182 end += 4
00183 (length,) = _struct_I.unpack(str[start:end])
00184 self.point_cloud.fields = []
00185 for i in range(0, length):
00186 val1 = sensor_msgs.msg.PointField()
00187 start = end
00188 end += 4
00189 (length,) = _struct_I.unpack(str[start:end])
00190 start = end
00191 end += length
00192 if python3:
00193 val1.name = str[start:end].decode('utf-8')
00194 else:
00195 val1.name = str[start:end]
00196 _x = val1
00197 start = end
00198 end += 9
00199 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00200 self.point_cloud.fields.append(val1)
00201 _x = self
00202 start = end
00203 end += 9
00204 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00205 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
00206 start = end
00207 end += 4
00208 (length,) = _struct_I.unpack(str[start:end])
00209 start = end
00210 end += length
00211 if python3:
00212 self.point_cloud.data = str[start:end].decode('utf-8')
00213 else:
00214 self.point_cloud.data = str[start:end]
00215 start = end
00216 end += 1
00217 (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
00218 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
00219 return self
00220 except struct.error as e:
00221 raise genpy.DeserializationError(e)
00222
00223
00224 def serialize_numpy(self, buff, numpy):
00225 """
00226 serialize message with numpy array types into buffer
00227 :param buff: buffer, ``StringIO``
00228 :param numpy: numpy python module
00229 """
00230 try:
00231 _x = self
00232 buff.write(_struct_3I.pack(_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs))
00233 _x = self.point_cloud.header.frame_id
00234 length = len(_x)
00235 if python3 or type(_x) == unicode:
00236 _x = _x.encode('utf-8')
00237 length = len(_x)
00238 buff.write(struct.pack('<I%ss'%length, length, _x))
00239 _x = self
00240 buff.write(_struct_2I.pack(_x.point_cloud.height, _x.point_cloud.width))
00241 length = len(self.point_cloud.fields)
00242 buff.write(_struct_I.pack(length))
00243 for val1 in self.point_cloud.fields:
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 _x = val1
00251 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00252 _x = self
00253 buff.write(_struct_B2I.pack(_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step))
00254 _x = self.point_cloud.data
00255 length = len(_x)
00256
00257 if type(_x) in [list, tuple]:
00258 buff.write(struct.pack('<I%sB'%length, length, *_x))
00259 else:
00260 buff.write(struct.pack('<I%ss'%length, length, _x))
00261 buff.write(_struct_B.pack(self.point_cloud.is_dense))
00262 except struct.error as se: self._check_types(se)
00263 except TypeError as te: self._check_types(te)
00264
00265 def deserialize_numpy(self, str, numpy):
00266 """
00267 unpack serialized message in str into this message instance using numpy for array types
00268 :param str: byte array of serialized message, ``str``
00269 :param numpy: numpy python module
00270 """
00271 try:
00272 if self.point_cloud is None:
00273 self.point_cloud = sensor_msgs.msg.PointCloud2()
00274 end = 0
00275 _x = self
00276 start = end
00277 end += 12
00278 (_x.point_cloud.header.seq, _x.point_cloud.header.stamp.secs, _x.point_cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00279 start = end
00280 end += 4
00281 (length,) = _struct_I.unpack(str[start:end])
00282 start = end
00283 end += length
00284 if python3:
00285 self.point_cloud.header.frame_id = str[start:end].decode('utf-8')
00286 else:
00287 self.point_cloud.header.frame_id = str[start:end]
00288 _x = self
00289 start = end
00290 end += 8
00291 (_x.point_cloud.height, _x.point_cloud.width,) = _struct_2I.unpack(str[start:end])
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 self.point_cloud.fields = []
00296 for i in range(0, length):
00297 val1 = sensor_msgs.msg.PointField()
00298 start = end
00299 end += 4
00300 (length,) = _struct_I.unpack(str[start:end])
00301 start = end
00302 end += length
00303 if python3:
00304 val1.name = str[start:end].decode('utf-8')
00305 else:
00306 val1.name = str[start:end]
00307 _x = val1
00308 start = end
00309 end += 9
00310 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00311 self.point_cloud.fields.append(val1)
00312 _x = self
00313 start = end
00314 end += 9
00315 (_x.point_cloud.is_bigendian, _x.point_cloud.point_step, _x.point_cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00316 self.point_cloud.is_bigendian = bool(self.point_cloud.is_bigendian)
00317 start = end
00318 end += 4
00319 (length,) = _struct_I.unpack(str[start:end])
00320 start = end
00321 end += length
00322 if python3:
00323 self.point_cloud.data = str[start:end].decode('utf-8')
00324 else:
00325 self.point_cloud.data = str[start:end]
00326 start = end
00327 end += 1
00328 (self.point_cloud.is_dense,) = _struct_B.unpack(str[start:end])
00329 self.point_cloud.is_dense = bool(self.point_cloud.is_dense)
00330 return self
00331 except struct.error as e:
00332 raise genpy.DeserializationError(e)
00333
00334 _struct_I = genpy.struct_I
00335 _struct_IBI = struct.Struct("<IBI")
00336 _struct_3I = struct.Struct("<3I")
00337 _struct_B = struct.Struct("<B")
00338 _struct_2I = struct.Struct("<2I")
00339 _struct_B2I = struct.Struct("<B2I")
00340 """autogenerated by genpy from zyonz_msgs/GetProbingStepsResponse.msg. Do not edit."""
00341 import sys
00342 python3 = True if sys.hexversion > 0x03000000 else False
00343 import genpy
00344 import struct
00345
00346 import zyonz_msgs.msg
00347 import geometry_msgs.msg
00348 import std_msgs.msg
00349
00350 class GetProbingStepsResponse(genpy.Message):
00351 _md5sum = "2a66e42dd171a8e974f4590dd30e3cb9"
00352 _type = "zyonz_msgs/GetProbingStepsResponse"
00353 _has_header = False
00354 _full_text = """
00355 zyonz_msgs/ProbingSteps[] steps
00356
00357
00358 ================================================================================
00359 MSG: zyonz_msgs/ProbingSteps
00360 geometry_msgs/PoseArray pre_probing
00361 geometry_msgs/PoseStamped probing
00362 geometry_msgs/PoseArray post_probing
00363
00364 ================================================================================
00365 MSG: geometry_msgs/PoseArray
00366 # An array of poses with a header for global reference.
00367
00368 Header header
00369
00370 Pose[] poses
00371
00372 ================================================================================
00373 MSG: std_msgs/Header
00374 # Standard metadata for higher-level stamped data types.
00375 # This is generally used to communicate timestamped data
00376 # in a particular coordinate frame.
00377 #
00378 # sequence ID: consecutively increasing ID
00379 uint32 seq
00380 #Two-integer timestamp that is expressed as:
00381 # * stamp.secs: seconds (stamp_secs) since epoch
00382 # * stamp.nsecs: nanoseconds since stamp_secs
00383 # time-handling sugar is provided by the client library
00384 time stamp
00385 #Frame this data is associated with
00386 # 0: no frame
00387 # 1: global frame
00388 string frame_id
00389
00390 ================================================================================
00391 MSG: geometry_msgs/Pose
00392 # A representation of pose in free space, composed of postion and orientation.
00393 Point position
00394 Quaternion orientation
00395
00396 ================================================================================
00397 MSG: geometry_msgs/Point
00398 # This contains the position of a point in free space
00399 float64 x
00400 float64 y
00401 float64 z
00402
00403 ================================================================================
00404 MSG: geometry_msgs/Quaternion
00405 # This represents an orientation in free space in quaternion form.
00406
00407 float64 x
00408 float64 y
00409 float64 z
00410 float64 w
00411
00412 ================================================================================
00413 MSG: geometry_msgs/PoseStamped
00414 # A Pose with reference coordinate frame and timestamp
00415 Header header
00416 Pose pose
00417
00418 """
00419 __slots__ = ['steps']
00420 _slot_types = ['zyonz_msgs/ProbingSteps[]']
00421
00422 def __init__(self, *args, **kwds):
00423 """
00424 Constructor. Any message fields that are implicitly/explicitly
00425 set to None will be assigned a default value. The recommend
00426 use is keyword arguments as this is more robust to future message
00427 changes. You cannot mix in-order arguments and keyword arguments.
00428
00429 The available fields are:
00430 steps
00431
00432 :param args: complete set of field values, in .msg order
00433 :param kwds: use keyword arguments corresponding to message field names
00434 to set specific fields.
00435 """
00436 if args or kwds:
00437 super(GetProbingStepsResponse, self).__init__(*args, **kwds)
00438
00439 if self.steps is None:
00440 self.steps = []
00441 else:
00442 self.steps = []
00443
00444 def _get_types(self):
00445 """
00446 internal API method
00447 """
00448 return self._slot_types
00449
00450 def serialize(self, buff):
00451 """
00452 serialize message into buffer
00453 :param buff: buffer, ``StringIO``
00454 """
00455 try:
00456 length = len(self.steps)
00457 buff.write(_struct_I.pack(length))
00458 for val1 in self.steps:
00459 _v1 = val1.pre_probing
00460 _v2 = _v1.header
00461 buff.write(_struct_I.pack(_v2.seq))
00462 _v3 = _v2.stamp
00463 _x = _v3
00464 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00465 _x = _v2.frame_id
00466 length = len(_x)
00467 if python3 or type(_x) == unicode:
00468 _x = _x.encode('utf-8')
00469 length = len(_x)
00470 buff.write(struct.pack('<I%ss'%length, length, _x))
00471 length = len(_v1.poses)
00472 buff.write(_struct_I.pack(length))
00473 for val3 in _v1.poses:
00474 _v4 = val3.position
00475 _x = _v4
00476 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00477 _v5 = val3.orientation
00478 _x = _v5
00479 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00480 _v6 = val1.probing
00481 _v7 = _v6.header
00482 buff.write(_struct_I.pack(_v7.seq))
00483 _v8 = _v7.stamp
00484 _x = _v8
00485 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00486 _x = _v7.frame_id
00487 length = len(_x)
00488 if python3 or type(_x) == unicode:
00489 _x = _x.encode('utf-8')
00490 length = len(_x)
00491 buff.write(struct.pack('<I%ss'%length, length, _x))
00492 _v9 = _v6.pose
00493 _v10 = _v9.position
00494 _x = _v10
00495 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00496 _v11 = _v9.orientation
00497 _x = _v11
00498 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00499 _v12 = val1.post_probing
00500 _v13 = _v12.header
00501 buff.write(_struct_I.pack(_v13.seq))
00502 _v14 = _v13.stamp
00503 _x = _v14
00504 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00505 _x = _v13.frame_id
00506 length = len(_x)
00507 if python3 or type(_x) == unicode:
00508 _x = _x.encode('utf-8')
00509 length = len(_x)
00510 buff.write(struct.pack('<I%ss'%length, length, _x))
00511 length = len(_v12.poses)
00512 buff.write(_struct_I.pack(length))
00513 for val3 in _v12.poses:
00514 _v15 = val3.position
00515 _x = _v15
00516 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00517 _v16 = val3.orientation
00518 _x = _v16
00519 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00520 except struct.error as se: self._check_types(se)
00521 except TypeError as te: self._check_types(te)
00522
00523 def deserialize(self, str):
00524 """
00525 unpack serialized message in str into this message instance
00526 :param str: byte array of serialized message, ``str``
00527 """
00528 try:
00529 if self.steps is None:
00530 self.steps = None
00531 end = 0
00532 start = end
00533 end += 4
00534 (length,) = _struct_I.unpack(str[start:end])
00535 self.steps = []
00536 for i in range(0, length):
00537 val1 = zyonz_msgs.msg.ProbingSteps()
00538 _v17 = val1.pre_probing
00539 _v18 = _v17.header
00540 start = end
00541 end += 4
00542 (_v18.seq,) = _struct_I.unpack(str[start:end])
00543 _v19 = _v18.stamp
00544 _x = _v19
00545 start = end
00546 end += 8
00547 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00548 start = end
00549 end += 4
00550 (length,) = _struct_I.unpack(str[start:end])
00551 start = end
00552 end += length
00553 if python3:
00554 _v18.frame_id = str[start:end].decode('utf-8')
00555 else:
00556 _v18.frame_id = str[start:end]
00557 start = end
00558 end += 4
00559 (length,) = _struct_I.unpack(str[start:end])
00560 _v17.poses = []
00561 for i in range(0, length):
00562 val3 = geometry_msgs.msg.Pose()
00563 _v20 = val3.position
00564 _x = _v20
00565 start = end
00566 end += 24
00567 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00568 _v21 = val3.orientation
00569 _x = _v21
00570 start = end
00571 end += 32
00572 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00573 _v17.poses.append(val3)
00574 _v22 = val1.probing
00575 _v23 = _v22.header
00576 start = end
00577 end += 4
00578 (_v23.seq,) = _struct_I.unpack(str[start:end])
00579 _v24 = _v23.stamp
00580 _x = _v24
00581 start = end
00582 end += 8
00583 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00584 start = end
00585 end += 4
00586 (length,) = _struct_I.unpack(str[start:end])
00587 start = end
00588 end += length
00589 if python3:
00590 _v23.frame_id = str[start:end].decode('utf-8')
00591 else:
00592 _v23.frame_id = str[start:end]
00593 _v25 = _v22.pose
00594 _v26 = _v25.position
00595 _x = _v26
00596 start = end
00597 end += 24
00598 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00599 _v27 = _v25.orientation
00600 _x = _v27
00601 start = end
00602 end += 32
00603 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00604 _v28 = val1.post_probing
00605 _v29 = _v28.header
00606 start = end
00607 end += 4
00608 (_v29.seq,) = _struct_I.unpack(str[start:end])
00609 _v30 = _v29.stamp
00610 _x = _v30
00611 start = end
00612 end += 8
00613 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00614 start = end
00615 end += 4
00616 (length,) = _struct_I.unpack(str[start:end])
00617 start = end
00618 end += length
00619 if python3:
00620 _v29.frame_id = str[start:end].decode('utf-8')
00621 else:
00622 _v29.frame_id = str[start:end]
00623 start = end
00624 end += 4
00625 (length,) = _struct_I.unpack(str[start:end])
00626 _v28.poses = []
00627 for i in range(0, length):
00628 val3 = geometry_msgs.msg.Pose()
00629 _v31 = val3.position
00630 _x = _v31
00631 start = end
00632 end += 24
00633 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00634 _v32 = val3.orientation
00635 _x = _v32
00636 start = end
00637 end += 32
00638 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00639 _v28.poses.append(val3)
00640 self.steps.append(val1)
00641 return self
00642 except struct.error as e:
00643 raise genpy.DeserializationError(e)
00644
00645
00646 def serialize_numpy(self, buff, numpy):
00647 """
00648 serialize message with numpy array types into buffer
00649 :param buff: buffer, ``StringIO``
00650 :param numpy: numpy python module
00651 """
00652 try:
00653 length = len(self.steps)
00654 buff.write(_struct_I.pack(length))
00655 for val1 in self.steps:
00656 _v33 = val1.pre_probing
00657 _v34 = _v33.header
00658 buff.write(_struct_I.pack(_v34.seq))
00659 _v35 = _v34.stamp
00660 _x = _v35
00661 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00662 _x = _v34.frame_id
00663 length = len(_x)
00664 if python3 or type(_x) == unicode:
00665 _x = _x.encode('utf-8')
00666 length = len(_x)
00667 buff.write(struct.pack('<I%ss'%length, length, _x))
00668 length = len(_v33.poses)
00669 buff.write(_struct_I.pack(length))
00670 for val3 in _v33.poses:
00671 _v36 = val3.position
00672 _x = _v36
00673 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00674 _v37 = val3.orientation
00675 _x = _v37
00676 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00677 _v38 = val1.probing
00678 _v39 = _v38.header
00679 buff.write(_struct_I.pack(_v39.seq))
00680 _v40 = _v39.stamp
00681 _x = _v40
00682 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00683 _x = _v39.frame_id
00684 length = len(_x)
00685 if python3 or type(_x) == unicode:
00686 _x = _x.encode('utf-8')
00687 length = len(_x)
00688 buff.write(struct.pack('<I%ss'%length, length, _x))
00689 _v41 = _v38.pose
00690 _v42 = _v41.position
00691 _x = _v42
00692 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00693 _v43 = _v41.orientation
00694 _x = _v43
00695 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00696 _v44 = val1.post_probing
00697 _v45 = _v44.header
00698 buff.write(_struct_I.pack(_v45.seq))
00699 _v46 = _v45.stamp
00700 _x = _v46
00701 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00702 _x = _v45.frame_id
00703 length = len(_x)
00704 if python3 or type(_x) == unicode:
00705 _x = _x.encode('utf-8')
00706 length = len(_x)
00707 buff.write(struct.pack('<I%ss'%length, length, _x))
00708 length = len(_v44.poses)
00709 buff.write(_struct_I.pack(length))
00710 for val3 in _v44.poses:
00711 _v47 = val3.position
00712 _x = _v47
00713 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00714 _v48 = val3.orientation
00715 _x = _v48
00716 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00717 except struct.error as se: self._check_types(se)
00718 except TypeError as te: self._check_types(te)
00719
00720 def deserialize_numpy(self, str, numpy):
00721 """
00722 unpack serialized message in str into this message instance using numpy for array types
00723 :param str: byte array of serialized message, ``str``
00724 :param numpy: numpy python module
00725 """
00726 try:
00727 if self.steps is None:
00728 self.steps = None
00729 end = 0
00730 start = end
00731 end += 4
00732 (length,) = _struct_I.unpack(str[start:end])
00733 self.steps = []
00734 for i in range(0, length):
00735 val1 = zyonz_msgs.msg.ProbingSteps()
00736 _v49 = val1.pre_probing
00737 _v50 = _v49.header
00738 start = end
00739 end += 4
00740 (_v50.seq,) = _struct_I.unpack(str[start:end])
00741 _v51 = _v50.stamp
00742 _x = _v51
00743 start = end
00744 end += 8
00745 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00746 start = end
00747 end += 4
00748 (length,) = _struct_I.unpack(str[start:end])
00749 start = end
00750 end += length
00751 if python3:
00752 _v50.frame_id = str[start:end].decode('utf-8')
00753 else:
00754 _v50.frame_id = str[start:end]
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 _v49.poses = []
00759 for i in range(0, length):
00760 val3 = geometry_msgs.msg.Pose()
00761 _v52 = val3.position
00762 _x = _v52
00763 start = end
00764 end += 24
00765 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00766 _v53 = val3.orientation
00767 _x = _v53
00768 start = end
00769 end += 32
00770 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00771 _v49.poses.append(val3)
00772 _v54 = val1.probing
00773 _v55 = _v54.header
00774 start = end
00775 end += 4
00776 (_v55.seq,) = _struct_I.unpack(str[start:end])
00777 _v56 = _v55.stamp
00778 _x = _v56
00779 start = end
00780 end += 8
00781 (_x.secs, _x.nsecs,) = _struct_2I.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 _v55.frame_id = str[start:end].decode('utf-8')
00789 else:
00790 _v55.frame_id = str[start:end]
00791 _v57 = _v54.pose
00792 _v58 = _v57.position
00793 _x = _v58
00794 start = end
00795 end += 24
00796 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00797 _v59 = _v57.orientation
00798 _x = _v59
00799 start = end
00800 end += 32
00801 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00802 _v60 = val1.post_probing
00803 _v61 = _v60.header
00804 start = end
00805 end += 4
00806 (_v61.seq,) = _struct_I.unpack(str[start:end])
00807 _v62 = _v61.stamp
00808 _x = _v62
00809 start = end
00810 end += 8
00811 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00812 start = end
00813 end += 4
00814 (length,) = _struct_I.unpack(str[start:end])
00815 start = end
00816 end += length
00817 if python3:
00818 _v61.frame_id = str[start:end].decode('utf-8')
00819 else:
00820 _v61.frame_id = str[start:end]
00821 start = end
00822 end += 4
00823 (length,) = _struct_I.unpack(str[start:end])
00824 _v60.poses = []
00825 for i in range(0, length):
00826 val3 = geometry_msgs.msg.Pose()
00827 _v63 = val3.position
00828 _x = _v63
00829 start = end
00830 end += 24
00831 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00832 _v64 = val3.orientation
00833 _x = _v64
00834 start = end
00835 end += 32
00836 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00837 _v60.poses.append(val3)
00838 self.steps.append(val1)
00839 return self
00840 except struct.error as e:
00841 raise genpy.DeserializationError(e)
00842
00843 _struct_I = genpy.struct_I
00844 _struct_4d = struct.Struct("<4d")
00845 _struct_2I = struct.Struct("<2I")
00846 _struct_3d = struct.Struct("<3d")
00847 class GetProbingSteps(object):
00848 _type = 'zyonz_msgs/GetProbingSteps'
00849 _md5sum = '9270ebd9b370226436a589229f5d2f04'
00850 _request_class = GetProbingStepsRequest
00851 _response_class = GetProbingStepsResponse