_RefScanRos.py
Go to the documentation of this file.
00001 """autogenerated by genpy from flirtlib_ros/RefScanRos.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import geometry_msgs.msg
00008 import flirtlib_ros.msg
00009 import std_msgs.msg
00010 import sensor_msgs.msg
00011 
00012 class RefScanRos(genpy.Message):
00013   _md5sum = "11956f8796f4796e1612ff817c3f3dca"
00014   _type = "flirtlib_ros/RefScanRos"
00015   _has_header = False #flag to mark the presence of a Header object
00016   _full_text = """sensor_msgs/LaserScan scan
00017 geometry_msgs/Pose pose
00018 InterestPointRos[] pts
00019 ================================================================================
00020 MSG: sensor_msgs/LaserScan
00021 # Single scan from a planar laser range-finder
00022 #
00023 # If you have another ranging device with different behavior (e.g. a sonar
00024 # array), please find or create a different message, since applications
00025 # will make fairly laser-specific assumptions about this data
00026 
00027 Header header            # timestamp in the header is the acquisition time of 
00028                          # the first ray in the scan.
00029                          #
00030                          # in frame frame_id, angles are measured around 
00031                          # the positive Z axis (counterclockwise, if Z is up)
00032                          # with zero angle being forward along the x axis
00033                          
00034 float32 angle_min        # start angle of the scan [rad]
00035 float32 angle_max        # end angle of the scan [rad]
00036 float32 angle_increment  # angular distance between measurements [rad]
00037 
00038 float32 time_increment   # time between measurements [seconds] - if your scanner
00039                          # is moving, this will be used in interpolating position
00040                          # of 3d points
00041 float32 scan_time        # time between scans [seconds]
00042 
00043 float32 range_min        # minimum range value [m]
00044 float32 range_max        # maximum range value [m]
00045 
00046 float32[] ranges         # range data [m] (Note: values < range_min or > range_max should be discarded)
00047 float32[] intensities    # intensity data [device-specific units].  If your
00048                          # device does not provide intensities, please leave
00049                          # the array empty.
00050 
00051 ================================================================================
00052 MSG: std_msgs/Header
00053 # Standard metadata for higher-level stamped data types.
00054 # This is generally used to communicate timestamped data 
00055 # in a particular coordinate frame.
00056 # 
00057 # sequence ID: consecutively increasing ID 
00058 uint32 seq
00059 #Two-integer timestamp that is expressed as:
00060 # * stamp.secs: seconds (stamp_secs) since epoch
00061 # * stamp.nsecs: nanoseconds since stamp_secs
00062 # time-handling sugar is provided by the client library
00063 time stamp
00064 #Frame this data is associated with
00065 # 0: no frame
00066 # 1: global frame
00067 string frame_id
00068 
00069 ================================================================================
00070 MSG: geometry_msgs/Pose
00071 # A representation of pose in free space, composed of postion and orientation. 
00072 Point position
00073 Quaternion orientation
00074 
00075 ================================================================================
00076 MSG: geometry_msgs/Point
00077 # This contains the position of a point in free space
00078 float64 x
00079 float64 y
00080 float64 z
00081 
00082 ================================================================================
00083 MSG: geometry_msgs/Quaternion
00084 # This represents an orientation in free space in quaternion form.
00085 
00086 float64 x
00087 float64 y
00088 float64 z
00089 float64 w
00090 
00091 ================================================================================
00092 MSG: flirtlib_ros/InterestPointRos
00093 # Corresponds to the InterestPoint type in flirtlib
00094 # Includes both the point location and optionally a descriptor
00095 
00096 geometry_msgs/Pose2D pose
00097 
00098 geometry_msgs/Point[] support_points
00099 
00100 float32 scale
00101 
00102 uint32 scale_level
00103 
00104 DescriptorRos descriptor
00105 
00106 
00107 ================================================================================
00108 MSG: geometry_msgs/Pose2D
00109 # This expresses a position and orientation on a 2D manifold.
00110 
00111 float64 x
00112 float64 y
00113 float64 theta
00114 ================================================================================
00115 MSG: flirtlib_ros/DescriptorRos
00116 # Confirms to the Descriptor type in flirtlib
00117 # For now, we only allow the beta grid descriptor
00118 
00119 Vector[] hist
00120 Vector[] variance
00121 Vector[] hit
00122 Vector[] miss
00123 
00124 ================================================================================
00125 MSG: flirtlib_ros/Vector
00126 # Vector message type used by a bunch of the flirtlib messages
00127 
00128 float64[] vec
00129 """
00130   __slots__ = ['scan','pose','pts']
00131   _slot_types = ['sensor_msgs/LaserScan','geometry_msgs/Pose','flirtlib_ros/InterestPointRos[]']
00132 
00133   def __init__(self, *args, **kwds):
00134     """
00135     Constructor. Any message fields that are implicitly/explicitly
00136     set to None will be assigned a default value. The recommend
00137     use is keyword arguments as this is more robust to future message
00138     changes.  You cannot mix in-order arguments and keyword arguments.
00139 
00140     The available fields are:
00141        scan,pose,pts
00142 
00143     :param args: complete set of field values, in .msg order
00144     :param kwds: use keyword arguments corresponding to message field names
00145     to set specific fields.
00146     """
00147     if args or kwds:
00148       super(RefScanRos, self).__init__(*args, **kwds)
00149       #message fields cannot be None, assign default values for those that are
00150       if self.scan is None:
00151         self.scan = sensor_msgs.msg.LaserScan()
00152       if self.pose is None:
00153         self.pose = geometry_msgs.msg.Pose()
00154       if self.pts is None:
00155         self.pts = []
00156     else:
00157       self.scan = sensor_msgs.msg.LaserScan()
00158       self.pose = geometry_msgs.msg.Pose()
00159       self.pts = []
00160 
00161   def _get_types(self):
00162     """
00163     internal API method
00164     """
00165     return self._slot_types
00166 
00167   def serialize(self, buff):
00168     """
00169     serialize message into buffer
00170     :param buff: buffer, ``StringIO``
00171     """
00172     try:
00173       _x = self
00174       buff.write(_struct_3I.pack(_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs))
00175       _x = self.scan.header.frame_id
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_7f.pack(_x.scan.angle_min, _x.scan.angle_max, _x.scan.angle_increment, _x.scan.time_increment, _x.scan.scan_time, _x.scan.range_min, _x.scan.range_max))
00183       length = len(self.scan.ranges)
00184       buff.write(_struct_I.pack(length))
00185       pattern = '<%sf'%length
00186       buff.write(struct.pack(pattern, *self.scan.ranges))
00187       length = len(self.scan.intensities)
00188       buff.write(_struct_I.pack(length))
00189       pattern = '<%sf'%length
00190       buff.write(struct.pack(pattern, *self.scan.intensities))
00191       _x = self
00192       buff.write(_struct_7d.pack(_x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w))
00193       length = len(self.pts)
00194       buff.write(_struct_I.pack(length))
00195       for val1 in self.pts:
00196         _v1 = val1.pose
00197         _x = _v1
00198         buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00199         length = len(val1.support_points)
00200         buff.write(_struct_I.pack(length))
00201         for val2 in val1.support_points:
00202           _x = val2
00203           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00204         _x = val1
00205         buff.write(_struct_fI.pack(_x.scale, _x.scale_level))
00206         _v2 = val1.descriptor
00207         length = len(_v2.hist)
00208         buff.write(_struct_I.pack(length))
00209         for val3 in _v2.hist:
00210           length = len(val3.vec)
00211           buff.write(_struct_I.pack(length))
00212           pattern = '<%sd'%length
00213           buff.write(struct.pack(pattern, *val3.vec))
00214         length = len(_v2.variance)
00215         buff.write(_struct_I.pack(length))
00216         for val3 in _v2.variance:
00217           length = len(val3.vec)
00218           buff.write(_struct_I.pack(length))
00219           pattern = '<%sd'%length
00220           buff.write(struct.pack(pattern, *val3.vec))
00221         length = len(_v2.hit)
00222         buff.write(_struct_I.pack(length))
00223         for val3 in _v2.hit:
00224           length = len(val3.vec)
00225           buff.write(_struct_I.pack(length))
00226           pattern = '<%sd'%length
00227           buff.write(struct.pack(pattern, *val3.vec))
00228         length = len(_v2.miss)
00229         buff.write(_struct_I.pack(length))
00230         for val3 in _v2.miss:
00231           length = len(val3.vec)
00232           buff.write(_struct_I.pack(length))
00233           pattern = '<%sd'%length
00234           buff.write(struct.pack(pattern, *val3.vec))
00235     except struct.error as se: self._check_types(se)
00236     except TypeError as te: self._check_types(te)
00237 
00238   def deserialize(self, str):
00239     """
00240     unpack serialized message in str into this message instance
00241     :param str: byte array of serialized message, ``str``
00242     """
00243     try:
00244       if self.scan is None:
00245         self.scan = sensor_msgs.msg.LaserScan()
00246       if self.pose is None:
00247         self.pose = geometry_msgs.msg.Pose()
00248       if self.pts is None:
00249         self.pts = None
00250       end = 0
00251       _x = self
00252       start = end
00253       end += 12
00254       (_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00255       start = end
00256       end += 4
00257       (length,) = _struct_I.unpack(str[start:end])
00258       start = end
00259       end += length
00260       if python3:
00261         self.scan.header.frame_id = str[start:end].decode('utf-8')
00262       else:
00263         self.scan.header.frame_id = str[start:end]
00264       _x = self
00265       start = end
00266       end += 28
00267       (_x.scan.angle_min, _x.scan.angle_max, _x.scan.angle_increment, _x.scan.time_increment, _x.scan.scan_time, _x.scan.range_min, _x.scan.range_max,) = _struct_7f.unpack(str[start:end])
00268       start = end
00269       end += 4
00270       (length,) = _struct_I.unpack(str[start:end])
00271       pattern = '<%sf'%length
00272       start = end
00273       end += struct.calcsize(pattern)
00274       self.scan.ranges = struct.unpack(pattern, str[start:end])
00275       start = end
00276       end += 4
00277       (length,) = _struct_I.unpack(str[start:end])
00278       pattern = '<%sf'%length
00279       start = end
00280       end += struct.calcsize(pattern)
00281       self.scan.intensities = struct.unpack(pattern, str[start:end])
00282       _x = self
00283       start = end
00284       end += 56
00285       (_x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00286       start = end
00287       end += 4
00288       (length,) = _struct_I.unpack(str[start:end])
00289       self.pts = []
00290       for i in range(0, length):
00291         val1 = flirtlib_ros.msg.InterestPointRos()
00292         _v3 = val1.pose
00293         _x = _v3
00294         start = end
00295         end += 24
00296         (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00297         start = end
00298         end += 4
00299         (length,) = _struct_I.unpack(str[start:end])
00300         val1.support_points = []
00301         for i in range(0, length):
00302           val2 = geometry_msgs.msg.Point()
00303           _x = val2
00304           start = end
00305           end += 24
00306           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00307           val1.support_points.append(val2)
00308         _x = val1
00309         start = end
00310         end += 8
00311         (_x.scale, _x.scale_level,) = _struct_fI.unpack(str[start:end])
00312         _v4 = val1.descriptor
00313         start = end
00314         end += 4
00315         (length,) = _struct_I.unpack(str[start:end])
00316         _v4.hist = []
00317         for i in range(0, length):
00318           val3 = flirtlib_ros.msg.Vector()
00319           start = end
00320           end += 4
00321           (length,) = _struct_I.unpack(str[start:end])
00322           pattern = '<%sd'%length
00323           start = end
00324           end += struct.calcsize(pattern)
00325           val3.vec = struct.unpack(pattern, str[start:end])
00326           _v4.hist.append(val3)
00327         start = end
00328         end += 4
00329         (length,) = _struct_I.unpack(str[start:end])
00330         _v4.variance = []
00331         for i in range(0, length):
00332           val3 = flirtlib_ros.msg.Vector()
00333           start = end
00334           end += 4
00335           (length,) = _struct_I.unpack(str[start:end])
00336           pattern = '<%sd'%length
00337           start = end
00338           end += struct.calcsize(pattern)
00339           val3.vec = struct.unpack(pattern, str[start:end])
00340           _v4.variance.append(val3)
00341         start = end
00342         end += 4
00343         (length,) = _struct_I.unpack(str[start:end])
00344         _v4.hit = []
00345         for i in range(0, length):
00346           val3 = flirtlib_ros.msg.Vector()
00347           start = end
00348           end += 4
00349           (length,) = _struct_I.unpack(str[start:end])
00350           pattern = '<%sd'%length
00351           start = end
00352           end += struct.calcsize(pattern)
00353           val3.vec = struct.unpack(pattern, str[start:end])
00354           _v4.hit.append(val3)
00355         start = end
00356         end += 4
00357         (length,) = _struct_I.unpack(str[start:end])
00358         _v4.miss = []
00359         for i in range(0, length):
00360           val3 = flirtlib_ros.msg.Vector()
00361           start = end
00362           end += 4
00363           (length,) = _struct_I.unpack(str[start:end])
00364           pattern = '<%sd'%length
00365           start = end
00366           end += struct.calcsize(pattern)
00367           val3.vec = struct.unpack(pattern, str[start:end])
00368           _v4.miss.append(val3)
00369         self.pts.append(val1)
00370       return self
00371     except struct.error as e:
00372       raise genpy.DeserializationError(e) #most likely buffer underfill
00373 
00374 
00375   def serialize_numpy(self, buff, numpy):
00376     """
00377     serialize message with numpy array types into buffer
00378     :param buff: buffer, ``StringIO``
00379     :param numpy: numpy python module
00380     """
00381     try:
00382       _x = self
00383       buff.write(_struct_3I.pack(_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs))
00384       _x = self.scan.header.frame_id
00385       length = len(_x)
00386       if python3 or type(_x) == unicode:
00387         _x = _x.encode('utf-8')
00388         length = len(_x)
00389       buff.write(struct.pack('<I%ss'%length, length, _x))
00390       _x = self
00391       buff.write(_struct_7f.pack(_x.scan.angle_min, _x.scan.angle_max, _x.scan.angle_increment, _x.scan.time_increment, _x.scan.scan_time, _x.scan.range_min, _x.scan.range_max))
00392       length = len(self.scan.ranges)
00393       buff.write(_struct_I.pack(length))
00394       pattern = '<%sf'%length
00395       buff.write(self.scan.ranges.tostring())
00396       length = len(self.scan.intensities)
00397       buff.write(_struct_I.pack(length))
00398       pattern = '<%sf'%length
00399       buff.write(self.scan.intensities.tostring())
00400       _x = self
00401       buff.write(_struct_7d.pack(_x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w))
00402       length = len(self.pts)
00403       buff.write(_struct_I.pack(length))
00404       for val1 in self.pts:
00405         _v5 = val1.pose
00406         _x = _v5
00407         buff.write(_struct_3d.pack(_x.x, _x.y, _x.theta))
00408         length = len(val1.support_points)
00409         buff.write(_struct_I.pack(length))
00410         for val2 in val1.support_points:
00411           _x = val2
00412           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00413         _x = val1
00414         buff.write(_struct_fI.pack(_x.scale, _x.scale_level))
00415         _v6 = val1.descriptor
00416         length = len(_v6.hist)
00417         buff.write(_struct_I.pack(length))
00418         for val3 in _v6.hist:
00419           length = len(val3.vec)
00420           buff.write(_struct_I.pack(length))
00421           pattern = '<%sd'%length
00422           buff.write(val3.vec.tostring())
00423         length = len(_v6.variance)
00424         buff.write(_struct_I.pack(length))
00425         for val3 in _v6.variance:
00426           length = len(val3.vec)
00427           buff.write(_struct_I.pack(length))
00428           pattern = '<%sd'%length
00429           buff.write(val3.vec.tostring())
00430         length = len(_v6.hit)
00431         buff.write(_struct_I.pack(length))
00432         for val3 in _v6.hit:
00433           length = len(val3.vec)
00434           buff.write(_struct_I.pack(length))
00435           pattern = '<%sd'%length
00436           buff.write(val3.vec.tostring())
00437         length = len(_v6.miss)
00438         buff.write(_struct_I.pack(length))
00439         for val3 in _v6.miss:
00440           length = len(val3.vec)
00441           buff.write(_struct_I.pack(length))
00442           pattern = '<%sd'%length
00443           buff.write(val3.vec.tostring())
00444     except struct.error as se: self._check_types(se)
00445     except TypeError as te: self._check_types(te)
00446 
00447   def deserialize_numpy(self, str, numpy):
00448     """
00449     unpack serialized message in str into this message instance using numpy for array types
00450     :param str: byte array of serialized message, ``str``
00451     :param numpy: numpy python module
00452     """
00453     try:
00454       if self.scan is None:
00455         self.scan = sensor_msgs.msg.LaserScan()
00456       if self.pose is None:
00457         self.pose = geometry_msgs.msg.Pose()
00458       if self.pts is None:
00459         self.pts = None
00460       end = 0
00461       _x = self
00462       start = end
00463       end += 12
00464       (_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00465       start = end
00466       end += 4
00467       (length,) = _struct_I.unpack(str[start:end])
00468       start = end
00469       end += length
00470       if python3:
00471         self.scan.header.frame_id = str[start:end].decode('utf-8')
00472       else:
00473         self.scan.header.frame_id = str[start:end]
00474       _x = self
00475       start = end
00476       end += 28
00477       (_x.scan.angle_min, _x.scan.angle_max, _x.scan.angle_increment, _x.scan.time_increment, _x.scan.scan_time, _x.scan.range_min, _x.scan.range_max,) = _struct_7f.unpack(str[start:end])
00478       start = end
00479       end += 4
00480       (length,) = _struct_I.unpack(str[start:end])
00481       pattern = '<%sf'%length
00482       start = end
00483       end += struct.calcsize(pattern)
00484       self.scan.ranges = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00485       start = end
00486       end += 4
00487       (length,) = _struct_I.unpack(str[start:end])
00488       pattern = '<%sf'%length
00489       start = end
00490       end += struct.calcsize(pattern)
00491       self.scan.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00492       _x = self
00493       start = end
00494       end += 56
00495       (_x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00496       start = end
00497       end += 4
00498       (length,) = _struct_I.unpack(str[start:end])
00499       self.pts = []
00500       for i in range(0, length):
00501         val1 = flirtlib_ros.msg.InterestPointRos()
00502         _v7 = val1.pose
00503         _x = _v7
00504         start = end
00505         end += 24
00506         (_x.x, _x.y, _x.theta,) = _struct_3d.unpack(str[start:end])
00507         start = end
00508         end += 4
00509         (length,) = _struct_I.unpack(str[start:end])
00510         val1.support_points = []
00511         for i in range(0, length):
00512           val2 = geometry_msgs.msg.Point()
00513           _x = val2
00514           start = end
00515           end += 24
00516           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00517           val1.support_points.append(val2)
00518         _x = val1
00519         start = end
00520         end += 8
00521         (_x.scale, _x.scale_level,) = _struct_fI.unpack(str[start:end])
00522         _v8 = val1.descriptor
00523         start = end
00524         end += 4
00525         (length,) = _struct_I.unpack(str[start:end])
00526         _v8.hist = []
00527         for i in range(0, length):
00528           val3 = flirtlib_ros.msg.Vector()
00529           start = end
00530           end += 4
00531           (length,) = _struct_I.unpack(str[start:end])
00532           pattern = '<%sd'%length
00533           start = end
00534           end += struct.calcsize(pattern)
00535           val3.vec = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00536           _v8.hist.append(val3)
00537         start = end
00538         end += 4
00539         (length,) = _struct_I.unpack(str[start:end])
00540         _v8.variance = []
00541         for i in range(0, length):
00542           val3 = flirtlib_ros.msg.Vector()
00543           start = end
00544           end += 4
00545           (length,) = _struct_I.unpack(str[start:end])
00546           pattern = '<%sd'%length
00547           start = end
00548           end += struct.calcsize(pattern)
00549           val3.vec = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00550           _v8.variance.append(val3)
00551         start = end
00552         end += 4
00553         (length,) = _struct_I.unpack(str[start:end])
00554         _v8.hit = []
00555         for i in range(0, length):
00556           val3 = flirtlib_ros.msg.Vector()
00557           start = end
00558           end += 4
00559           (length,) = _struct_I.unpack(str[start:end])
00560           pattern = '<%sd'%length
00561           start = end
00562           end += struct.calcsize(pattern)
00563           val3.vec = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00564           _v8.hit.append(val3)
00565         start = end
00566         end += 4
00567         (length,) = _struct_I.unpack(str[start:end])
00568         _v8.miss = []
00569         for i in range(0, length):
00570           val3 = flirtlib_ros.msg.Vector()
00571           start = end
00572           end += 4
00573           (length,) = _struct_I.unpack(str[start:end])
00574           pattern = '<%sd'%length
00575           start = end
00576           end += struct.calcsize(pattern)
00577           val3.vec = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00578           _v8.miss.append(val3)
00579         self.pts.append(val1)
00580       return self
00581     except struct.error as e:
00582       raise genpy.DeserializationError(e) #most likely buffer underfill
00583 
00584 _struct_I = genpy.struct_I
00585 _struct_7f = struct.Struct("<7f")
00586 _struct_3I = struct.Struct("<3I")
00587 _struct_7d = struct.Struct("<7d")
00588 _struct_fI = struct.Struct("<fI")
00589 _struct_3d = struct.Struct("<3d")


flirtlib_ros
Author(s): Bhaskara Marthi
autogenerated on Thu Nov 28 2013 11:21:50