00001 """autogenerated by genmsg_py from MapMetaData.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import roslib.rostime
00007
00008 class MapMetaData(roslib.message.Message):
00009 _md5sum = "10cfc8a2818024d3248802c00c95f11b"
00010 _type = "nav_msgs/MapMetaData"
00011 _has_header = False
00012 _full_text = """# This hold basic information about the characterists of the OccupancyGrid
00013
00014 # The time at which the map was loaded
00015 time map_load_time
00016 # The map resolution [m/cell]
00017 float32 resolution
00018 # Map width [cells]
00019 uint32 width
00020 # Map height [cells]
00021 uint32 height
00022 # The origin of the map [m, m, rad]. This is the real-world pose of the
00023 # cell (0,0) in the map.
00024 geometry_msgs/Pose origin
00025 ================================================================================
00026 MSG: geometry_msgs/Pose
00027 # A representation of pose in free space, composed of postion and orientation.
00028 Point position
00029 Quaternion orientation
00030
00031 ================================================================================
00032 MSG: geometry_msgs/Point
00033 # This contains the position of a point in free space
00034 float64 x
00035 float64 y
00036 float64 z
00037
00038 ================================================================================
00039 MSG: geometry_msgs/Quaternion
00040 # This represents an orientation in free space in quaternion form.
00041
00042 float64 x
00043 float64 y
00044 float64 z
00045 float64 w
00046
00047 """
00048 __slots__ = ['map_load_time','resolution','width','height','origin']
00049 _slot_types = ['time','float32','uint32','uint32','geometry_msgs/Pose']
00050
00051 def __init__(self, *args, **kwds):
00052 """
00053 Constructor. Any message fields that are implicitly/explicitly
00054 set to None will be assigned a default value. The recommend
00055 use is keyword arguments as this is more robust to future message
00056 changes. You cannot mix in-order arguments and keyword arguments.
00057
00058 The available fields are:
00059 map_load_time,resolution,width,height,origin
00060
00061 @param args: complete set of field values, in .msg order
00062 @param kwds: use keyword arguments corresponding to message field names
00063 to set specific fields.
00064 """
00065 if args or kwds:
00066 super(MapMetaData, self).__init__(*args, **kwds)
00067
00068 if self.map_load_time is None:
00069 self.map_load_time = roslib.rostime.Time()
00070 if self.resolution is None:
00071 self.resolution = 0.
00072 if self.width is None:
00073 self.width = 0
00074 if self.height is None:
00075 self.height = 0
00076 if self.origin is None:
00077 self.origin = geometry_msgs.msg.Pose()
00078 else:
00079 self.map_load_time = roslib.rostime.Time()
00080 self.resolution = 0.
00081 self.width = 0
00082 self.height = 0
00083 self.origin = geometry_msgs.msg.Pose()
00084
00085 def _get_types(self):
00086 """
00087 internal API method
00088 """
00089 return self._slot_types
00090
00091 def serialize(self, buff):
00092 """
00093 serialize message into buffer
00094 @param buff: buffer
00095 @type buff: StringIO
00096 """
00097 try:
00098 _x = self
00099 buff.write(_struct_2If2I7d.pack(_x.map_load_time.secs, _x.map_load_time.nsecs, _x.resolution, _x.width, _x.height, _x.origin.position.x, _x.origin.position.y, _x.origin.position.z, _x.origin.orientation.x, _x.origin.orientation.y, _x.origin.orientation.z, _x.origin.orientation.w))
00100 except struct.error as se: self._check_types(se)
00101 except TypeError as te: self._check_types(te)
00102
00103 def deserialize(self, str):
00104 """
00105 unpack serialized message in str into this message instance
00106 @param str: byte array of serialized message
00107 @type str: str
00108 """
00109 try:
00110 if self.map_load_time is None:
00111 self.map_load_time = roslib.rostime.Time()
00112 if self.origin is None:
00113 self.origin = geometry_msgs.msg.Pose()
00114 end = 0
00115 _x = self
00116 start = end
00117 end += 76
00118 (_x.map_load_time.secs, _x.map_load_time.nsecs, _x.resolution, _x.width, _x.height, _x.origin.position.x, _x.origin.position.y, _x.origin.position.z, _x.origin.orientation.x, _x.origin.orientation.y, _x.origin.orientation.z, _x.origin.orientation.w,) = _struct_2If2I7d.unpack(str[start:end])
00119 self.map_load_time.canon()
00120 return self
00121 except struct.error as e:
00122 raise roslib.message.DeserializationError(e)
00123
00124
00125 def serialize_numpy(self, buff, numpy):
00126 """
00127 serialize message with numpy array types into buffer
00128 @param buff: buffer
00129 @type buff: StringIO
00130 @param numpy: numpy python module
00131 @type numpy module
00132 """
00133 try:
00134 _x = self
00135 buff.write(_struct_2If2I7d.pack(_x.map_load_time.secs, _x.map_load_time.nsecs, _x.resolution, _x.width, _x.height, _x.origin.position.x, _x.origin.position.y, _x.origin.position.z, _x.origin.orientation.x, _x.origin.orientation.y, _x.origin.orientation.z, _x.origin.orientation.w))
00136 except struct.error as se: self._check_types(se)
00137 except TypeError as te: self._check_types(te)
00138
00139 def deserialize_numpy(self, str, numpy):
00140 """
00141 unpack serialized message in str into this message instance using numpy for array types
00142 @param str: byte array of serialized message
00143 @type str: str
00144 @param numpy: numpy python module
00145 @type numpy: module
00146 """
00147 try:
00148 if self.map_load_time is None:
00149 self.map_load_time = roslib.rostime.Time()
00150 if self.origin is None:
00151 self.origin = geometry_msgs.msg.Pose()
00152 end = 0
00153 _x = self
00154 start = end
00155 end += 76
00156 (_x.map_load_time.secs, _x.map_load_time.nsecs, _x.resolution, _x.width, _x.height, _x.origin.position.x, _x.origin.position.y, _x.origin.position.z, _x.origin.orientation.x, _x.origin.orientation.y, _x.origin.orientation.z, _x.origin.orientation.w,) = _struct_2If2I7d.unpack(str[start:end])
00157 self.map_load_time.canon()
00158 return self
00159 except struct.error as e:
00160 raise roslib.message.DeserializationError(e)
00161
00162 _struct_I = roslib.message.struct_I
00163 _struct_2If2I7d = struct.Struct("<2If2I7d")