00001 """autogenerated by genpy from nasa_r2_common_msgs/SystemStatus.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 nasa_r2_common_msgs.msg
00008 import genpy
00009 import std_msgs.msg
00010
00011 class SystemStatus(genpy.Message):
00012 _md5sum = "4896af13a56b5d046a8dac4145b244f0"
00013 _type = "nasa_r2_common_msgs/SystemStatus"
00014 _has_header = True
00015 _full_text = """Header header
00016 string name
00017 SystemCore[] coreStats
00018 float64[] coreTemps
00019 float64 oneMinuteLoad
00020 float64 fiveMinuteLoad
00021 float64 fifteenMinuteLoad
00022 duration uptime
00023 uint32 totalMemory
00024 uint32 usedMemory
00025 uint32 freeMemory
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: nasa_r2_common_msgs/SystemCore
00046 string id
00047 float64 speed
00048 float64 load
00049 bool failure
00050 """
00051 __slots__ = ['header','name','coreStats','coreTemps','oneMinuteLoad','fiveMinuteLoad','fifteenMinuteLoad','uptime','totalMemory','usedMemory','freeMemory']
00052 _slot_types = ['std_msgs/Header','string','nasa_r2_common_msgs/SystemCore[]','float64[]','float64','float64','float64','duration','uint32','uint32','uint32']
00053
00054 def __init__(self, *args, **kwds):
00055 """
00056 Constructor. Any message fields that are implicitly/explicitly
00057 set to None will be assigned a default value. The recommend
00058 use is keyword arguments as this is more robust to future message
00059 changes. You cannot mix in-order arguments and keyword arguments.
00060
00061 The available fields are:
00062 header,name,coreStats,coreTemps,oneMinuteLoad,fiveMinuteLoad,fifteenMinuteLoad,uptime,totalMemory,usedMemory,freeMemory
00063
00064 :param args: complete set of field values, in .msg order
00065 :param kwds: use keyword arguments corresponding to message field names
00066 to set specific fields.
00067 """
00068 if args or kwds:
00069 super(SystemStatus, self).__init__(*args, **kwds)
00070
00071 if self.header is None:
00072 self.header = std_msgs.msg.Header()
00073 if self.name is None:
00074 self.name = ''
00075 if self.coreStats is None:
00076 self.coreStats = []
00077 if self.coreTemps is None:
00078 self.coreTemps = []
00079 if self.oneMinuteLoad is None:
00080 self.oneMinuteLoad = 0.
00081 if self.fiveMinuteLoad is None:
00082 self.fiveMinuteLoad = 0.
00083 if self.fifteenMinuteLoad is None:
00084 self.fifteenMinuteLoad = 0.
00085 if self.uptime is None:
00086 self.uptime = genpy.Duration()
00087 if self.totalMemory is None:
00088 self.totalMemory = 0
00089 if self.usedMemory is None:
00090 self.usedMemory = 0
00091 if self.freeMemory is None:
00092 self.freeMemory = 0
00093 else:
00094 self.header = std_msgs.msg.Header()
00095 self.name = ''
00096 self.coreStats = []
00097 self.coreTemps = []
00098 self.oneMinuteLoad = 0.
00099 self.fiveMinuteLoad = 0.
00100 self.fifteenMinuteLoad = 0.
00101 self.uptime = genpy.Duration()
00102 self.totalMemory = 0
00103 self.usedMemory = 0
00104 self.freeMemory = 0
00105
00106 def _get_types(self):
00107 """
00108 internal API method
00109 """
00110 return self._slot_types
00111
00112 def serialize(self, buff):
00113 """
00114 serialize message into buffer
00115 :param buff: buffer, ``StringIO``
00116 """
00117 try:
00118 _x = self
00119 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00120 _x = self.header.frame_id
00121 length = len(_x)
00122 if python3 or type(_x) == unicode:
00123 _x = _x.encode('utf-8')
00124 length = len(_x)
00125 buff.write(struct.pack('<I%ss'%length, length, _x))
00126 _x = self.name
00127 length = len(_x)
00128 if python3 or type(_x) == unicode:
00129 _x = _x.encode('utf-8')
00130 length = len(_x)
00131 buff.write(struct.pack('<I%ss'%length, length, _x))
00132 length = len(self.coreStats)
00133 buff.write(_struct_I.pack(length))
00134 for val1 in self.coreStats:
00135 _x = val1.id
00136 length = len(_x)
00137 if python3 or type(_x) == unicode:
00138 _x = _x.encode('utf-8')
00139 length = len(_x)
00140 buff.write(struct.pack('<I%ss'%length, length, _x))
00141 _x = val1
00142 buff.write(_struct_2dB.pack(_x.speed, _x.load, _x.failure))
00143 length = len(self.coreTemps)
00144 buff.write(_struct_I.pack(length))
00145 pattern = '<%sd'%length
00146 buff.write(struct.pack(pattern, *self.coreTemps))
00147 _x = self
00148 buff.write(_struct_3d2i3I.pack(_x.oneMinuteLoad, _x.fiveMinuteLoad, _x.fifteenMinuteLoad, _x.uptime.secs, _x.uptime.nsecs, _x.totalMemory, _x.usedMemory, _x.freeMemory))
00149 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00150 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00151
00152 def deserialize(self, str):
00153 """
00154 unpack serialized message in str into this message instance
00155 :param str: byte array of serialized message, ``str``
00156 """
00157 try:
00158 if self.header is None:
00159 self.header = std_msgs.msg.Header()
00160 if self.coreStats is None:
00161 self.coreStats = None
00162 if self.uptime is None:
00163 self.uptime = genpy.Duration()
00164 end = 0
00165 _x = self
00166 start = end
00167 end += 12
00168 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00169 start = end
00170 end += 4
00171 (length,) = _struct_I.unpack(str[start:end])
00172 start = end
00173 end += length
00174 if python3:
00175 self.header.frame_id = str[start:end].decode('utf-8')
00176 else:
00177 self.header.frame_id = str[start:end]
00178 start = end
00179 end += 4
00180 (length,) = _struct_I.unpack(str[start:end])
00181 start = end
00182 end += length
00183 if python3:
00184 self.name = str[start:end].decode('utf-8')
00185 else:
00186 self.name = str[start:end]
00187 start = end
00188 end += 4
00189 (length,) = _struct_I.unpack(str[start:end])
00190 self.coreStats = []
00191 for i in range(0, length):
00192 val1 = nasa_r2_common_msgs.msg.SystemCore()
00193 start = end
00194 end += 4
00195 (length,) = _struct_I.unpack(str[start:end])
00196 start = end
00197 end += length
00198 if python3:
00199 val1.id = str[start:end].decode('utf-8')
00200 else:
00201 val1.id = str[start:end]
00202 _x = val1
00203 start = end
00204 end += 17
00205 (_x.speed, _x.load, _x.failure,) = _struct_2dB.unpack(str[start:end])
00206 val1.failure = bool(val1.failure)
00207 self.coreStats.append(val1)
00208 start = end
00209 end += 4
00210 (length,) = _struct_I.unpack(str[start:end])
00211 pattern = '<%sd'%length
00212 start = end
00213 end += struct.calcsize(pattern)
00214 self.coreTemps = struct.unpack(pattern, str[start:end])
00215 _x = self
00216 start = end
00217 end += 44
00218 (_x.oneMinuteLoad, _x.fiveMinuteLoad, _x.fifteenMinuteLoad, _x.uptime.secs, _x.uptime.nsecs, _x.totalMemory, _x.usedMemory, _x.freeMemory,) = _struct_3d2i3I.unpack(str[start:end])
00219 self.uptime.canon()
00220 return self
00221 except struct.error as e:
00222 raise genpy.DeserializationError(e)
00223
00224
00225 def serialize_numpy(self, buff, numpy):
00226 """
00227 serialize message with numpy array types into buffer
00228 :param buff: buffer, ``StringIO``
00229 :param numpy: numpy python module
00230 """
00231 try:
00232 _x = self
00233 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00234 _x = self.header.frame_id
00235 length = len(_x)
00236 if python3 or type(_x) == unicode:
00237 _x = _x.encode('utf-8')
00238 length = len(_x)
00239 buff.write(struct.pack('<I%ss'%length, length, _x))
00240 _x = self.name
00241 length = len(_x)
00242 if python3 or type(_x) == unicode:
00243 _x = _x.encode('utf-8')
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 length = len(self.coreStats)
00247 buff.write(_struct_I.pack(length))
00248 for val1 in self.coreStats:
00249 _x = val1.id
00250 length = len(_x)
00251 if python3 or type(_x) == unicode:
00252 _x = _x.encode('utf-8')
00253 length = len(_x)
00254 buff.write(struct.pack('<I%ss'%length, length, _x))
00255 _x = val1
00256 buff.write(_struct_2dB.pack(_x.speed, _x.load, _x.failure))
00257 length = len(self.coreTemps)
00258 buff.write(_struct_I.pack(length))
00259 pattern = '<%sd'%length
00260 buff.write(self.coreTemps.tostring())
00261 _x = self
00262 buff.write(_struct_3d2i3I.pack(_x.oneMinuteLoad, _x.fiveMinuteLoad, _x.fifteenMinuteLoad, _x.uptime.secs, _x.uptime.nsecs, _x.totalMemory, _x.usedMemory, _x.freeMemory))
00263 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00264 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00265
00266 def deserialize_numpy(self, str, numpy):
00267 """
00268 unpack serialized message in str into this message instance using numpy for array types
00269 :param str: byte array of serialized message, ``str``
00270 :param numpy: numpy python module
00271 """
00272 try:
00273 if self.header is None:
00274 self.header = std_msgs.msg.Header()
00275 if self.coreStats is None:
00276 self.coreStats = None
00277 if self.uptime is None:
00278 self.uptime = genpy.Duration()
00279 end = 0
00280 _x = self
00281 start = end
00282 end += 12
00283 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00284 start = end
00285 end += 4
00286 (length,) = _struct_I.unpack(str[start:end])
00287 start = end
00288 end += length
00289 if python3:
00290 self.header.frame_id = str[start:end].decode('utf-8')
00291 else:
00292 self.header.frame_id = str[start:end]
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 start = end
00297 end += length
00298 if python3:
00299 self.name = str[start:end].decode('utf-8')
00300 else:
00301 self.name = str[start:end]
00302 start = end
00303 end += 4
00304 (length,) = _struct_I.unpack(str[start:end])
00305 self.coreStats = []
00306 for i in range(0, length):
00307 val1 = nasa_r2_common_msgs.msg.SystemCore()
00308 start = end
00309 end += 4
00310 (length,) = _struct_I.unpack(str[start:end])
00311 start = end
00312 end += length
00313 if python3:
00314 val1.id = str[start:end].decode('utf-8')
00315 else:
00316 val1.id = str[start:end]
00317 _x = val1
00318 start = end
00319 end += 17
00320 (_x.speed, _x.load, _x.failure,) = _struct_2dB.unpack(str[start:end])
00321 val1.failure = bool(val1.failure)
00322 self.coreStats.append(val1)
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 pattern = '<%sd'%length
00327 start = end
00328 end += struct.calcsize(pattern)
00329 self.coreTemps = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00330 _x = self
00331 start = end
00332 end += 44
00333 (_x.oneMinuteLoad, _x.fiveMinuteLoad, _x.fifteenMinuteLoad, _x.uptime.secs, _x.uptime.nsecs, _x.totalMemory, _x.usedMemory, _x.freeMemory,) = _struct_3d2i3I.unpack(str[start:end])
00334 self.uptime.canon()
00335 return self
00336 except struct.error as e:
00337 raise genpy.DeserializationError(e)
00338
00339 _struct_I = genpy.struct_I
00340 _struct_3I = struct.Struct("<3I")
00341 _struct_3d2i3I = struct.Struct("<3d2i3I")
00342 _struct_2dB = struct.Struct("<2dB")