_ProjectedMap.py
Go to the documentation of this file.
00001 """autogenerated by genpy from map_msgs/ProjectedMap.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 nav_msgs.msg
00009 import genpy
00010 import std_msgs.msg
00011 
00012 class ProjectedMap(genpy.Message):
00013   _md5sum = "7bbe8f96e45089681dc1ea7d023cbfca"
00014   _type = "map_msgs/ProjectedMap"
00015   _has_header = False #flag to mark the presence of a Header object
00016   _full_text = """nav_msgs/OccupancyGrid map
00017 float64 min_z
00018 float64 max_z
00019 ================================================================================
00020 MSG: nav_msgs/OccupancyGrid
00021 # This represents a 2-D grid map, in which each cell represents the probability of
00022 # occupancy.
00023 
00024 Header header 
00025 
00026 #MetaData for the map
00027 MapMetaData info
00028 
00029 # The map data, in row-major order, starting with (0,0).  Occupancy
00030 # probabilities are in the range [0,100].  Unknown is -1.
00031 int8[] data
00032 
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data 
00037 # in a particular coordinate frame.
00038 # 
00039 # sequence ID: consecutively increasing ID 
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050 
00051 ================================================================================
00052 MSG: nav_msgs/MapMetaData
00053 # This hold basic information about the characterists of the OccupancyGrid
00054 
00055 # The time at which the map was loaded
00056 time map_load_time
00057 # The map resolution [m/cell]
00058 float32 resolution
00059 # Map width [cells]
00060 uint32 width
00061 # Map height [cells]
00062 uint32 height
00063 # The origin of the map [m, m, rad].  This is the real-world pose of the
00064 # cell (0,0) in the map.
00065 geometry_msgs/Pose origin
00066 ================================================================================
00067 MSG: geometry_msgs/Pose
00068 # A representation of pose in free space, composed of postion and orientation. 
00069 Point position
00070 Quaternion orientation
00071 
00072 ================================================================================
00073 MSG: geometry_msgs/Point
00074 # This contains the position of a point in free space
00075 float64 x
00076 float64 y
00077 float64 z
00078 
00079 ================================================================================
00080 MSG: geometry_msgs/Quaternion
00081 # This represents an orientation in free space in quaternion form.
00082 
00083 float64 x
00084 float64 y
00085 float64 z
00086 float64 w
00087 
00088 """
00089   __slots__ = ['map','min_z','max_z']
00090   _slot_types = ['nav_msgs/OccupancyGrid','float64','float64']
00091 
00092   def __init__(self, *args, **kwds):
00093     """
00094     Constructor. Any message fields that are implicitly/explicitly
00095     set to None will be assigned a default value. The recommend
00096     use is keyword arguments as this is more robust to future message
00097     changes.  You cannot mix in-order arguments and keyword arguments.
00098 
00099     The available fields are:
00100        map,min_z,max_z
00101 
00102     :param args: complete set of field values, in .msg order
00103     :param kwds: use keyword arguments corresponding to message field names
00104     to set specific fields.
00105     """
00106     if args or kwds:
00107       super(ProjectedMap, self).__init__(*args, **kwds)
00108       #message fields cannot be None, assign default values for those that are
00109       if self.map is None:
00110         self.map = nav_msgs.msg.OccupancyGrid()
00111       if self.min_z is None:
00112         self.min_z = 0.
00113       if self.max_z is None:
00114         self.max_z = 0.
00115     else:
00116       self.map = nav_msgs.msg.OccupancyGrid()
00117       self.min_z = 0.
00118       self.max_z = 0.
00119 
00120   def _get_types(self):
00121     """
00122     internal API method
00123     """
00124     return self._slot_types
00125 
00126   def serialize(self, buff):
00127     """
00128     serialize message into buffer
00129     :param buff: buffer, ``StringIO``
00130     """
00131     try:
00132       _x = self
00133       buff.write(_struct_3I.pack(_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs))
00134       _x = self.map.header.frame_id
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 = self
00141       buff.write(_struct_2If2I7d.pack(_x.map.info.map_load_time.secs, _x.map.info.map_load_time.nsecs, _x.map.info.resolution, _x.map.info.width, _x.map.info.height, _x.map.info.origin.position.x, _x.map.info.origin.position.y, _x.map.info.origin.position.z, _x.map.info.origin.orientation.x, _x.map.info.origin.orientation.y, _x.map.info.origin.orientation.z, _x.map.info.origin.orientation.w))
00142       length = len(self.map.data)
00143       buff.write(_struct_I.pack(length))
00144       pattern = '<%sb'%length
00145       buff.write(struct.pack(pattern, *self.map.data))
00146       _x = self
00147       buff.write(_struct_2d.pack(_x.min_z, _x.max_z))
00148     except struct.error as se: self._check_types(se)
00149     except TypeError as te: self._check_types(te)
00150 
00151   def deserialize(self, str):
00152     """
00153     unpack serialized message in str into this message instance
00154     :param str: byte array of serialized message, ``str``
00155     """
00156     try:
00157       if self.map is None:
00158         self.map = nav_msgs.msg.OccupancyGrid()
00159       end = 0
00160       _x = self
00161       start = end
00162       end += 12
00163       (_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00164       start = end
00165       end += 4
00166       (length,) = _struct_I.unpack(str[start:end])
00167       start = end
00168       end += length
00169       if python3:
00170         self.map.header.frame_id = str[start:end].decode('utf-8')
00171       else:
00172         self.map.header.frame_id = str[start:end]
00173       _x = self
00174       start = end
00175       end += 76
00176       (_x.map.info.map_load_time.secs, _x.map.info.map_load_time.nsecs, _x.map.info.resolution, _x.map.info.width, _x.map.info.height, _x.map.info.origin.position.x, _x.map.info.origin.position.y, _x.map.info.origin.position.z, _x.map.info.origin.orientation.x, _x.map.info.origin.orientation.y, _x.map.info.origin.orientation.z, _x.map.info.origin.orientation.w,) = _struct_2If2I7d.unpack(str[start:end])
00177       start = end
00178       end += 4
00179       (length,) = _struct_I.unpack(str[start:end])
00180       pattern = '<%sb'%length
00181       start = end
00182       end += struct.calcsize(pattern)
00183       self.map.data = struct.unpack(pattern, str[start:end])
00184       _x = self
00185       start = end
00186       end += 16
00187       (_x.min_z, _x.max_z,) = _struct_2d.unpack(str[start:end])
00188       return self
00189     except struct.error as e:
00190       raise genpy.DeserializationError(e) #most likely buffer underfill
00191 
00192 
00193   def serialize_numpy(self, buff, numpy):
00194     """
00195     serialize message with numpy array types into buffer
00196     :param buff: buffer, ``StringIO``
00197     :param numpy: numpy python module
00198     """
00199     try:
00200       _x = self
00201       buff.write(_struct_3I.pack(_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs))
00202       _x = self.map.header.frame_id
00203       length = len(_x)
00204       if python3 or type(_x) == unicode:
00205         _x = _x.encode('utf-8')
00206         length = len(_x)
00207       buff.write(struct.pack('<I%ss'%length, length, _x))
00208       _x = self
00209       buff.write(_struct_2If2I7d.pack(_x.map.info.map_load_time.secs, _x.map.info.map_load_time.nsecs, _x.map.info.resolution, _x.map.info.width, _x.map.info.height, _x.map.info.origin.position.x, _x.map.info.origin.position.y, _x.map.info.origin.position.z, _x.map.info.origin.orientation.x, _x.map.info.origin.orientation.y, _x.map.info.origin.orientation.z, _x.map.info.origin.orientation.w))
00210       length = len(self.map.data)
00211       buff.write(_struct_I.pack(length))
00212       pattern = '<%sb'%length
00213       buff.write(self.map.data.tostring())
00214       _x = self
00215       buff.write(_struct_2d.pack(_x.min_z, _x.max_z))
00216     except struct.error as se: self._check_types(se)
00217     except TypeError as te: self._check_types(te)
00218 
00219   def deserialize_numpy(self, str, numpy):
00220     """
00221     unpack serialized message in str into this message instance using numpy for array types
00222     :param str: byte array of serialized message, ``str``
00223     :param numpy: numpy python module
00224     """
00225     try:
00226       if self.map is None:
00227         self.map = nav_msgs.msg.OccupancyGrid()
00228       end = 0
00229       _x = self
00230       start = end
00231       end += 12
00232       (_x.map.header.seq, _x.map.header.stamp.secs, _x.map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00233       start = end
00234       end += 4
00235       (length,) = _struct_I.unpack(str[start:end])
00236       start = end
00237       end += length
00238       if python3:
00239         self.map.header.frame_id = str[start:end].decode('utf-8')
00240       else:
00241         self.map.header.frame_id = str[start:end]
00242       _x = self
00243       start = end
00244       end += 76
00245       (_x.map.info.map_load_time.secs, _x.map.info.map_load_time.nsecs, _x.map.info.resolution, _x.map.info.width, _x.map.info.height, _x.map.info.origin.position.x, _x.map.info.origin.position.y, _x.map.info.origin.position.z, _x.map.info.origin.orientation.x, _x.map.info.origin.orientation.y, _x.map.info.origin.orientation.z, _x.map.info.origin.orientation.w,) = _struct_2If2I7d.unpack(str[start:end])
00246       start = end
00247       end += 4
00248       (length,) = _struct_I.unpack(str[start:end])
00249       pattern = '<%sb'%length
00250       start = end
00251       end += struct.calcsize(pattern)
00252       self.map.data = numpy.frombuffer(str[start:end], dtype=numpy.int8, count=length)
00253       _x = self
00254       start = end
00255       end += 16
00256       (_x.min_z, _x.max_z,) = _struct_2d.unpack(str[start:end])
00257       return self
00258     except struct.error as e:
00259       raise genpy.DeserializationError(e) #most likely buffer underfill
00260 
00261 _struct_I = genpy.struct_I
00262 _struct_2d = struct.Struct("<2d")
00263 _struct_3I = struct.Struct("<3I")
00264 _struct_2If2I7d = struct.Struct("<2If2I7d")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


map_msgs
Author(s): Stéphane Magnenat
autogenerated on Fri May 31 2013 08:22:01