00001 """autogenerated by genmsg_py from BatteryServer2.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import pr2_msgs.msg
00007 import std_msgs.msg
00008
00009 class BatteryServer2(roslib.message.Message):
00010 _md5sum = "5f2cec7d06c312d756189db96c1f3819"
00011 _type = "pr2_msgs/BatteryServer2"
00012 _has_header = True
00013 _full_text = """# This message communicates the state of a battery server, which controls
00014 # multiple batteries.
00015 Header header
00016 int32 MAX_BAT_COUNT=4
00017 int32 MAX_BAT_REG=48
00018 int32 id # unique ID for each battery server
00019 # Battery System Stats
00020 time last_system_update # last time the system stats where updated
00021 duration time_left # in seconds (hardware resolution is 1 minute)
00022 int32 average_charge # in percent
00023 string message # message from the ocean server
00024 time last_controller_update # last time a battery status flag was updated
00025 # for each battery
00026 pr2_msgs/BatteryState2[] battery
00027
00028 ================================================================================
00029 MSG: std_msgs/Header
00030 # Standard metadata for higher-level stamped data types.
00031 # This is generally used to communicate timestamped data
00032 # in a particular coordinate frame.
00033 #
00034 # sequence ID: consecutively increasing ID
00035 uint32 seq
00036 #Two-integer timestamp that is expressed as:
00037 # * stamp.secs: seconds (stamp_secs) since epoch
00038 # * stamp.nsecs: nanoseconds since stamp_secs
00039 # time-handling sugar is provided by the client library
00040 time stamp
00041 #Frame this data is associated with
00042 # 0: no frame
00043 # 1: global frame
00044 string frame_id
00045
00046 ================================================================================
00047 MSG: pr2_msgs/BatteryState2
00048 # This message communicates the state of a single battery.
00049 # Battery Controller Flags, one per battery
00050 bool present # is this pack present
00051 bool charging # is this pack charging
00052 bool discharging # is this pack discharging
00053 bool power_present # is there an input voltage
00054 bool power_no_good # is there a fault (No Good)
00055 bool inhibited # is this pack disabled for some reason
00056 # These registers are per battery
00057 time last_battery_update # last time any battery update occurred
00058 int16[48] battery_register # value of this register in the battery
00059 bool[48] battery_update_flag # Has this register ever been updated
00060 time[48] battery_register_update # last time this specific register was updated
00061
00062 """
00063
00064 MAX_BAT_COUNT = 4
00065 MAX_BAT_REG = 48
00066
00067 __slots__ = ['header','id','last_system_update','time_left','average_charge','message','last_controller_update','battery']
00068 _slot_types = ['Header','int32','time','duration','int32','string','time','pr2_msgs/BatteryState2[]']
00069
00070 def __init__(self, *args, **kwds):
00071 """
00072 Constructor. Any message fields that are implicitly/explicitly
00073 set to None will be assigned a default value. The recommend
00074 use is keyword arguments as this is more robust to future message
00075 changes. You cannot mix in-order arguments and keyword arguments.
00076
00077 The available fields are:
00078 header,id,last_system_update,time_left,average_charge,message,last_controller_update,battery
00079
00080 @param args: complete set of field values, in .msg order
00081 @param kwds: use keyword arguments corresponding to message field names
00082 to set specific fields.
00083 """
00084 if args or kwds:
00085 super(BatteryServer2, self).__init__(*args, **kwds)
00086
00087 if self.header is None:
00088 self.header = std_msgs.msg._Header.Header()
00089 if self.id is None:
00090 self.id = 0
00091 if self.last_system_update is None:
00092 self.last_system_update = roslib.rostime.Time()
00093 if self.time_left is None:
00094 self.time_left = roslib.rostime.Duration()
00095 if self.average_charge is None:
00096 self.average_charge = 0
00097 if self.message is None:
00098 self.message = ''
00099 if self.last_controller_update is None:
00100 self.last_controller_update = roslib.rostime.Time()
00101 if self.battery is None:
00102 self.battery = []
00103 else:
00104 self.header = std_msgs.msg._Header.Header()
00105 self.id = 0
00106 self.last_system_update = roslib.rostime.Time()
00107 self.time_left = roslib.rostime.Duration()
00108 self.average_charge = 0
00109 self.message = ''
00110 self.last_controller_update = roslib.rostime.Time()
00111 self.battery = []
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_i2I3i.pack(_x.id, _x.last_system_update.secs, _x.last_system_update.nsecs, _x.time_left.secs, _x.time_left.nsecs, _x.average_charge))
00133 _x = self.message
00134 length = len(_x)
00135 buff.write(struct.pack('<I%ss'%length, length, _x))
00136 _x = self
00137 buff.write(_struct_2I.pack(_x.last_controller_update.secs, _x.last_controller_update.nsecs))
00138 length = len(self.battery)
00139 buff.write(_struct_I.pack(length))
00140 for val1 in self.battery:
00141 _x = val1
00142 buff.write(_struct_6B.pack(_x.present, _x.charging, _x.discharging, _x.power_present, _x.power_no_good, _x.inhibited))
00143 _v1 = val1.last_battery_update
00144 _x = _v1
00145 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00146 buff.write(_struct_48h.pack(*val1.battery_register))
00147 buff.write(_struct_48B.pack(*val1.battery_update_flag))
00148 for val2 in val1.battery_register_update:
00149 _x = val2
00150 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00151 except struct.error, se: self._check_types(se)
00152 except TypeError, te: self._check_types(te)
00153
00154 def deserialize(self, str):
00155 """
00156 unpack serialized message in str into this message instance
00157 @param str: byte array of serialized message
00158 @type str: str
00159 """
00160 try:
00161 if self.header is None:
00162 self.header = std_msgs.msg._Header.Header()
00163 if self.last_system_update is None:
00164 self.last_system_update = roslib.rostime.Time()
00165 if self.time_left is None:
00166 self.time_left = roslib.rostime.Duration()
00167 if self.last_controller_update is None:
00168 self.last_controller_update = roslib.rostime.Time()
00169 end = 0
00170 _x = self
00171 start = end
00172 end += 12
00173 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00174 start = end
00175 end += 4
00176 (length,) = _struct_I.unpack(str[start:end])
00177 start = end
00178 end += length
00179 self.header.frame_id = str[start:end]
00180 _x = self
00181 start = end
00182 end += 24
00183 (_x.id, _x.last_system_update.secs, _x.last_system_update.nsecs, _x.time_left.secs, _x.time_left.nsecs, _x.average_charge,) = _struct_i2I3i.unpack(str[start:end])
00184 start = end
00185 end += 4
00186 (length,) = _struct_I.unpack(str[start:end])
00187 start = end
00188 end += length
00189 self.message = str[start:end]
00190 _x = self
00191 start = end
00192 end += 8
00193 (_x.last_controller_update.secs, _x.last_controller_update.nsecs,) = _struct_2I.unpack(str[start:end])
00194 start = end
00195 end += 4
00196 (length,) = _struct_I.unpack(str[start:end])
00197 self.battery = []
00198 for i in xrange(0, length):
00199 val1 = pr2_msgs.msg.BatteryState2()
00200 _x = val1
00201 start = end
00202 end += 6
00203 (_x.present, _x.charging, _x.discharging, _x.power_present, _x.power_no_good, _x.inhibited,) = _struct_6B.unpack(str[start:end])
00204 val1.present = bool(val1.present)
00205 val1.charging = bool(val1.charging)
00206 val1.discharging = bool(val1.discharging)
00207 val1.power_present = bool(val1.power_present)
00208 val1.power_no_good = bool(val1.power_no_good)
00209 val1.inhibited = bool(val1.inhibited)
00210 _v2 = val1.last_battery_update
00211 _x = _v2
00212 start = end
00213 end += 8
00214 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00215 start = end
00216 end += 96
00217 val1.battery_register = _struct_48h.unpack(str[start:end])
00218 start = end
00219 end += 48
00220 val1.battery_update_flag = _struct_48B.unpack(str[start:end])
00221 val1.battery_update_flag = map(bool, val1.battery_update_flag)
00222 val1.battery_register_update = []
00223 for i in xrange(0, 48):
00224 val2 = roslib.rostime.Time()
00225 _x = val2
00226 start = end
00227 end += 8
00228 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00229 val1.battery_register_update.append(val2)
00230 self.battery.append(val1)
00231 self.last_system_update.canon()
00232 self.time_left.canon()
00233 self.last_controller_update.canon()
00234 return self
00235 except struct.error, e:
00236 raise roslib.message.DeserializationError(e)
00237
00238
00239 def serialize_numpy(self, buff, numpy):
00240 """
00241 serialize message with numpy array types into buffer
00242 @param buff: buffer
00243 @type buff: StringIO
00244 @param numpy: numpy python module
00245 @type numpy module
00246 """
00247 try:
00248 _x = self
00249 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00250 _x = self.header.frame_id
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_i2I3i.pack(_x.id, _x.last_system_update.secs, _x.last_system_update.nsecs, _x.time_left.secs, _x.time_left.nsecs, _x.average_charge))
00255 _x = self.message
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 _x = self
00259 buff.write(_struct_2I.pack(_x.last_controller_update.secs, _x.last_controller_update.nsecs))
00260 length = len(self.battery)
00261 buff.write(_struct_I.pack(length))
00262 for val1 in self.battery:
00263 _x = val1
00264 buff.write(_struct_6B.pack(_x.present, _x.charging, _x.discharging, _x.power_present, _x.power_no_good, _x.inhibited))
00265 _v3 = val1.last_battery_update
00266 _x = _v3
00267 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00268 buff.write(val1.battery_register.tostring())
00269 buff.write(val1.battery_update_flag.tostring())
00270 for val2 in val1.battery_register_update:
00271 _x = val2
00272 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00273 except struct.error, se: self._check_types(se)
00274 except TypeError, te: self._check_types(te)
00275
00276 def deserialize_numpy(self, str, numpy):
00277 """
00278 unpack serialized message in str into this message instance using numpy for array types
00279 @param str: byte array of serialized message
00280 @type str: str
00281 @param numpy: numpy python module
00282 @type numpy: module
00283 """
00284 try:
00285 if self.header is None:
00286 self.header = std_msgs.msg._Header.Header()
00287 if self.last_system_update is None:
00288 self.last_system_update = roslib.rostime.Time()
00289 if self.time_left is None:
00290 self.time_left = roslib.rostime.Duration()
00291 if self.last_controller_update is None:
00292 self.last_controller_update = roslib.rostime.Time()
00293 end = 0
00294 _x = self
00295 start = end
00296 end += 12
00297 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00298 start = end
00299 end += 4
00300 (length,) = _struct_I.unpack(str[start:end])
00301 start = end
00302 end += length
00303 self.header.frame_id = str[start:end]
00304 _x = self
00305 start = end
00306 end += 24
00307 (_x.id, _x.last_system_update.secs, _x.last_system_update.nsecs, _x.time_left.secs, _x.time_left.nsecs, _x.average_charge,) = _struct_i2I3i.unpack(str[start:end])
00308 start = end
00309 end += 4
00310 (length,) = _struct_I.unpack(str[start:end])
00311 start = end
00312 end += length
00313 self.message = str[start:end]
00314 _x = self
00315 start = end
00316 end += 8
00317 (_x.last_controller_update.secs, _x.last_controller_update.nsecs,) = _struct_2I.unpack(str[start:end])
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 self.battery = []
00322 for i in xrange(0, length):
00323 val1 = pr2_msgs.msg.BatteryState2()
00324 _x = val1
00325 start = end
00326 end += 6
00327 (_x.present, _x.charging, _x.discharging, _x.power_present, _x.power_no_good, _x.inhibited,) = _struct_6B.unpack(str[start:end])
00328 val1.present = bool(val1.present)
00329 val1.charging = bool(val1.charging)
00330 val1.discharging = bool(val1.discharging)
00331 val1.power_present = bool(val1.power_present)
00332 val1.power_no_good = bool(val1.power_no_good)
00333 val1.inhibited = bool(val1.inhibited)
00334 _v4 = val1.last_battery_update
00335 _x = _v4
00336 start = end
00337 end += 8
00338 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00339 start = end
00340 end += 96
00341 val1.battery_register = numpy.frombuffer(str[start:end], dtype=numpy.int16, count=48)
00342 start = end
00343 end += 48
00344 val1.battery_update_flag = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=48)
00345 val1.battery_update_flag = map(bool, val1.battery_update_flag)
00346 val1.battery_register_update = []
00347 for i in xrange(0, 48):
00348 val2 = roslib.rostime.Time()
00349 _x = val2
00350 start = end
00351 end += 8
00352 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00353 val1.battery_register_update.append(val2)
00354 self.battery.append(val1)
00355 self.last_system_update.canon()
00356 self.time_left.canon()
00357 self.last_controller_update.canon()
00358 return self
00359 except struct.error, e:
00360 raise roslib.message.DeserializationError(e)
00361
00362 _struct_I = roslib.message.struct_I
00363 _struct_6B = struct.Struct("<6B")
00364 _struct_i2I3i = struct.Struct("<i2I3i")
00365 _struct_48h = struct.Struct("<48h")
00366 _struct_48B = struct.Struct("<48B")
00367 _struct_3I = struct.Struct("<3I")
00368 _struct_2I = struct.Struct("<2I")