00001 """autogenerated by genmsg_py from BatteryServer.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import pr2_msgs.msg
00006 import std_msgs.msg
00007
00008 class BatteryServer(roslib.message.Message):
00009 _md5sum = "4f6d6e54c9581beb1df7ea408c0727be"
00010 _type = "pr2_msgs/BatteryServer"
00011 _has_header = True
00012 _full_text = """# DEPRECATED. Use pr2_msgs/BatteryServer2 instead.
00013 Header header
00014 uint32 MAX_BAT_COUNT=4
00015 uint32 MAX_BAT_REG=48
00016 int32 id # unique ID for each battery server
00017 # Battery System Stats
00018 int32 lastTimeSystem #epoch time
00019 uint16 timeLeft # in minutes
00020 uint16 averageCharge # in percent
00021 string message
00022 # Battery Controller Flags
00023 int32 lastTimeController #epoch time
00024 uint16 present
00025 uint16 charging
00026 uint16 discharging
00027 uint16 reserved
00028 uint16 powerPresent
00029 uint16 powerNG
00030 uint16 inhibited
00031 # for each battery
00032 pr2_msgs/BatteryState[] battery
00033
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data
00038 # in a particular coordinate frame.
00039 #
00040 # sequence ID: consecutively increasing ID
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051
00052 ================================================================================
00053 MSG: pr2_msgs/BatteryState
00054 # DEPRECATED. Use pr2_msgs/BatteryState2 instead.
00055 # Each batteries registers
00056 int32 lastTimeBattery #epoch time
00057 uint16[48] batReg
00058 uint16[48] batRegFlag
00059 int32[48] batRegTime
00060
00061 """
00062
00063 MAX_BAT_COUNT = 4
00064 MAX_BAT_REG = 48
00065
00066 __slots__ = ['header','id','lastTimeSystem','timeLeft','averageCharge','message','lastTimeController','present','charging','discharging','reserved','powerPresent','powerNG','inhibited','battery']
00067 _slot_types = ['Header','int32','int32','uint16','uint16','string','int32','uint16','uint16','uint16','uint16','uint16','uint16','uint16','pr2_msgs/BatteryState[]']
00068
00069 def __init__(self, *args, **kwds):
00070 """
00071 Constructor. Any message fields that are implicitly/explicitly
00072 set to None will be assigned a default value. The recommend
00073 use is keyword arguments as this is more robust to future message
00074 changes. You cannot mix in-order arguments and keyword arguments.
00075
00076 The available fields are:
00077 header,id,lastTimeSystem,timeLeft,averageCharge,message,lastTimeController,present,charging,discharging,reserved,powerPresent,powerNG,inhibited,battery
00078
00079 @param args: complete set of field values, in .msg order
00080 @param kwds: use keyword arguments corresponding to message field names
00081 to set specific fields.
00082 """
00083 if args or kwds:
00084 super(BatteryServer, self).__init__(*args, **kwds)
00085
00086 if self.header is None:
00087 self.header = std_msgs.msg._Header.Header()
00088 if self.id is None:
00089 self.id = 0
00090 if self.lastTimeSystem is None:
00091 self.lastTimeSystem = 0
00092 if self.timeLeft is None:
00093 self.timeLeft = 0
00094 if self.averageCharge is None:
00095 self.averageCharge = 0
00096 if self.message is None:
00097 self.message = ''
00098 if self.lastTimeController is None:
00099 self.lastTimeController = 0
00100 if self.present is None:
00101 self.present = 0
00102 if self.charging is None:
00103 self.charging = 0
00104 if self.discharging is None:
00105 self.discharging = 0
00106 if self.reserved is None:
00107 self.reserved = 0
00108 if self.powerPresent is None:
00109 self.powerPresent = 0
00110 if self.powerNG is None:
00111 self.powerNG = 0
00112 if self.inhibited is None:
00113 self.inhibited = 0
00114 if self.battery is None:
00115 self.battery = []
00116 else:
00117 self.header = std_msgs.msg._Header.Header()
00118 self.id = 0
00119 self.lastTimeSystem = 0
00120 self.timeLeft = 0
00121 self.averageCharge = 0
00122 self.message = ''
00123 self.lastTimeController = 0
00124 self.present = 0
00125 self.charging = 0
00126 self.discharging = 0
00127 self.reserved = 0
00128 self.powerPresent = 0
00129 self.powerNG = 0
00130 self.inhibited = 0
00131 self.battery = []
00132
00133 def _get_types(self):
00134 """
00135 internal API method
00136 """
00137 return self._slot_types
00138
00139 def serialize(self, buff):
00140 """
00141 serialize message into buffer
00142 @param buff: buffer
00143 @type buff: StringIO
00144 """
00145 try:
00146 _x = self
00147 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00148 _x = self.header.frame_id
00149 length = len(_x)
00150 buff.write(struct.pack('<I%ss'%length, length, _x))
00151 _x = self
00152 buff.write(_struct_2i2H.pack(_x.id, _x.lastTimeSystem, _x.timeLeft, _x.averageCharge))
00153 _x = self.message
00154 length = len(_x)
00155 buff.write(struct.pack('<I%ss'%length, length, _x))
00156 _x = self
00157 buff.write(_struct_i7H.pack(_x.lastTimeController, _x.present, _x.charging, _x.discharging, _x.reserved, _x.powerPresent, _x.powerNG, _x.inhibited))
00158 length = len(self.battery)
00159 buff.write(_struct_I.pack(length))
00160 for val1 in self.battery:
00161 buff.write(_struct_i.pack(val1.lastTimeBattery))
00162 buff.write(_struct_48H.pack(*val1.batReg))
00163 buff.write(_struct_48H.pack(*val1.batRegFlag))
00164 buff.write(_struct_48i.pack(*val1.batRegTime))
00165 except struct.error, se: self._check_types(se)
00166 except TypeError, te: self._check_types(te)
00167
00168 def deserialize(self, str):
00169 """
00170 unpack serialized message in str into this message instance
00171 @param str: byte array of serialized message
00172 @type str: str
00173 """
00174 try:
00175 if self.header is None:
00176 self.header = std_msgs.msg._Header.Header()
00177 end = 0
00178 _x = self
00179 start = end
00180 end += 12
00181 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00182 start = end
00183 end += 4
00184 (length,) = _struct_I.unpack(str[start:end])
00185 start = end
00186 end += length
00187 self.header.frame_id = str[start:end]
00188 _x = self
00189 start = end
00190 end += 12
00191 (_x.id, _x.lastTimeSystem, _x.timeLeft, _x.averageCharge,) = _struct_2i2H.unpack(str[start:end])
00192 start = end
00193 end += 4
00194 (length,) = _struct_I.unpack(str[start:end])
00195 start = end
00196 end += length
00197 self.message = str[start:end]
00198 _x = self
00199 start = end
00200 end += 18
00201 (_x.lastTimeController, _x.present, _x.charging, _x.discharging, _x.reserved, _x.powerPresent, _x.powerNG, _x.inhibited,) = _struct_i7H.unpack(str[start:end])
00202 start = end
00203 end += 4
00204 (length,) = _struct_I.unpack(str[start:end])
00205 self.battery = []
00206 for i in xrange(0, length):
00207 val1 = pr2_msgs.msg.BatteryState()
00208 start = end
00209 end += 4
00210 (val1.lastTimeBattery,) = _struct_i.unpack(str[start:end])
00211 start = end
00212 end += 96
00213 val1.batReg = _struct_48H.unpack(str[start:end])
00214 start = end
00215 end += 96
00216 val1.batRegFlag = _struct_48H.unpack(str[start:end])
00217 start = end
00218 end += 192
00219 val1.batRegTime = _struct_48i.unpack(str[start:end])
00220 self.battery.append(val1)
00221 return self
00222 except struct.error, e:
00223 raise roslib.message.DeserializationError(e)
00224
00225
00226 def serialize_numpy(self, buff, numpy):
00227 """
00228 serialize message with numpy array types into buffer
00229 @param buff: buffer
00230 @type buff: StringIO
00231 @param numpy: numpy python module
00232 @type numpy module
00233 """
00234 try:
00235 _x = self
00236 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00237 _x = self.header.frame_id
00238 length = len(_x)
00239 buff.write(struct.pack('<I%ss'%length, length, _x))
00240 _x = self
00241 buff.write(_struct_2i2H.pack(_x.id, _x.lastTimeSystem, _x.timeLeft, _x.averageCharge))
00242 _x = self.message
00243 length = len(_x)
00244 buff.write(struct.pack('<I%ss'%length, length, _x))
00245 _x = self
00246 buff.write(_struct_i7H.pack(_x.lastTimeController, _x.present, _x.charging, _x.discharging, _x.reserved, _x.powerPresent, _x.powerNG, _x.inhibited))
00247 length = len(self.battery)
00248 buff.write(_struct_I.pack(length))
00249 for val1 in self.battery:
00250 buff.write(_struct_i.pack(val1.lastTimeBattery))
00251 buff.write(val1.batReg.tostring())
00252 buff.write(val1.batRegFlag.tostring())
00253 buff.write(val1.batRegTime.tostring())
00254 except struct.error, se: self._check_types(se)
00255 except TypeError, te: self._check_types(te)
00256
00257 def deserialize_numpy(self, str, numpy):
00258 """
00259 unpack serialized message in str into this message instance using numpy for array types
00260 @param str: byte array of serialized message
00261 @type str: str
00262 @param numpy: numpy python module
00263 @type numpy: module
00264 """
00265 try:
00266 if self.header is None:
00267 self.header = std_msgs.msg._Header.Header()
00268 end = 0
00269 _x = self
00270 start = end
00271 end += 12
00272 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00273 start = end
00274 end += 4
00275 (length,) = _struct_I.unpack(str[start:end])
00276 start = end
00277 end += length
00278 self.header.frame_id = str[start:end]
00279 _x = self
00280 start = end
00281 end += 12
00282 (_x.id, _x.lastTimeSystem, _x.timeLeft, _x.averageCharge,) = _struct_2i2H.unpack(str[start:end])
00283 start = end
00284 end += 4
00285 (length,) = _struct_I.unpack(str[start:end])
00286 start = end
00287 end += length
00288 self.message = str[start:end]
00289 _x = self
00290 start = end
00291 end += 18
00292 (_x.lastTimeController, _x.present, _x.charging, _x.discharging, _x.reserved, _x.powerPresent, _x.powerNG, _x.inhibited,) = _struct_i7H.unpack(str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 self.battery = []
00297 for i in xrange(0, length):
00298 val1 = pr2_msgs.msg.BatteryState()
00299 start = end
00300 end += 4
00301 (val1.lastTimeBattery,) = _struct_i.unpack(str[start:end])
00302 start = end
00303 end += 96
00304 val1.batReg = numpy.frombuffer(str[start:end], dtype=numpy.uint16, count=48)
00305 start = end
00306 end += 96
00307 val1.batRegFlag = numpy.frombuffer(str[start:end], dtype=numpy.uint16, count=48)
00308 start = end
00309 end += 192
00310 val1.batRegTime = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=48)
00311 self.battery.append(val1)
00312 return self
00313 except struct.error, e:
00314 raise roslib.message.DeserializationError(e)
00315
00316 _struct_I = roslib.message.struct_I
00317 _struct_2i2H = struct.Struct("<2i2H")
00318 _struct_48i = struct.Struct("<48i")
00319 _struct_48H = struct.Struct("<48H")
00320 _struct_i = struct.Struct("<i")
00321 _struct_i7H = struct.Struct("<i7H")
00322 _struct_3I = struct.Struct("<3I")