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