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