00001 """autogenerated by genpy from pr2_msgs/DashboardState.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 genpy
00008 import pr2_msgs.msg
00009 import std_msgs.msg
00010
00011 class DashboardState(genpy.Message):
00012 _md5sum = "db0cd0d535d75e0f6257b20c403e87f5"
00013 _type = "pr2_msgs/DashboardState"
00014 _has_header = False
00015 _full_text = """# This message communicates state information that might be used by a
00016 # dashboard application.
00017 std_msgs/Bool motors_halted
00018 bool motors_halted_valid
00019
00020 pr2_msgs/PowerBoardState power_board_state
00021 bool power_board_state_valid
00022
00023 pr2_msgs/PowerState power_state
00024 bool power_state_valid
00025
00026 pr2_msgs/AccessPoint access_point
00027 bool access_point_valid
00028
00029 ================================================================================
00030 MSG: std_msgs/Bool
00031 bool data
00032 ================================================================================
00033 MSG: pr2_msgs/PowerBoardState
00034 # This message communicates the state of the PR2's power board.
00035 int8 STATE_NOPOWER=0
00036 int8 STATE_STANDBY=1
00037 int8 STATE_PUMPING=2
00038 int8 STATE_ON=3
00039 int8 STATE_ENABLED=3 # Preferred over STATE_ON, keeping STATE_ON for backcompat
00040 int8 STATE_DISABLED=4
00041
00042 int8 MASTER_NOPOWER=0
00043 int8 MASTER_STANDBY=1
00044 int8 MASTER_ON=2
00045 int8 MASTER_OFF=3
00046 int8 MASTER_SHUTDOWN=4
00047
00048 Header header
00049 string name # Name with serial number
00050 uint32 serial_num # Serial number for this board's message
00051 float64 input_voltage # Input voltage to power board
00052
00053 # Master States:
00054 # MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN
00055 int8 master_state # The master state machine's state in the powerboard
00056
00057 # Circuit States:
00058 # STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED
00059 int8[3] circuit_state # One of the above states
00060 float64[3] circuit_voltage # Output voltage of each circuit
00061
00062 # True if robot should be enabled
00063 bool run_stop #Note - if the wireless run-stop is hit, this will be unobservable
00064 bool wireless_stop
00065
00066 ================================================================================
00067 MSG: std_msgs/Header
00068 # Standard metadata for higher-level stamped data types.
00069 # This is generally used to communicate timestamped data
00070 # in a particular coordinate frame.
00071 #
00072 # sequence ID: consecutively increasing ID
00073 uint32 seq
00074 #Two-integer timestamp that is expressed as:
00075 # * stamp.secs: seconds (stamp_secs) since epoch
00076 # * stamp.nsecs: nanoseconds since stamp_secs
00077 # time-handling sugar is provided by the client library
00078 time stamp
00079 #Frame this data is associated with
00080 # 0: no frame
00081 # 1: global frame
00082 string frame_id
00083
00084 ================================================================================
00085 MSG: pr2_msgs/PowerState
00086 # This message communicates the state of the PR2's power system.
00087 Header header
00088 float64 power_consumption ## Watts
00089 duration time_remaining ## estimated time to empty or full
00090 string prediction_method ## how time_remaining is being calculated
00091 int8 relative_capacity ## percent of capacity
00092 int8 AC_present ## number of packs detecting AC power, > 0 means plugged in
00093
00094 ================================================================================
00095 MSG: pr2_msgs/AccessPoint
00096 # This message communicates the state of the PR2's wifi access point.
00097 Header header
00098 string essid
00099 string macaddr
00100 int32 signal
00101 int32 noise
00102 int32 snr
00103 int32 channel
00104 string rate
00105 string tx_power
00106 int32 quality
00107
00108 """
00109 __slots__ = ['motors_halted','motors_halted_valid','power_board_state','power_board_state_valid','power_state','power_state_valid','access_point','access_point_valid']
00110 _slot_types = ['std_msgs/Bool','bool','pr2_msgs/PowerBoardState','bool','pr2_msgs/PowerState','bool','pr2_msgs/AccessPoint','bool']
00111
00112 def __init__(self, *args, **kwds):
00113 """
00114 Constructor. Any message fields that are implicitly/explicitly
00115 set to None will be assigned a default value. The recommend
00116 use is keyword arguments as this is more robust to future message
00117 changes. You cannot mix in-order arguments and keyword arguments.
00118
00119 The available fields are:
00120 motors_halted,motors_halted_valid,power_board_state,power_board_state_valid,power_state,power_state_valid,access_point,access_point_valid
00121
00122 :param args: complete set of field values, in .msg order
00123 :param kwds: use keyword arguments corresponding to message field names
00124 to set specific fields.
00125 """
00126 if args or kwds:
00127 super(DashboardState, self).__init__(*args, **kwds)
00128
00129 if self.motors_halted is None:
00130 self.motors_halted = std_msgs.msg.Bool()
00131 if self.motors_halted_valid is None:
00132 self.motors_halted_valid = False
00133 if self.power_board_state is None:
00134 self.power_board_state = pr2_msgs.msg.PowerBoardState()
00135 if self.power_board_state_valid is None:
00136 self.power_board_state_valid = False
00137 if self.power_state is None:
00138 self.power_state = pr2_msgs.msg.PowerState()
00139 if self.power_state_valid is None:
00140 self.power_state_valid = False
00141 if self.access_point is None:
00142 self.access_point = pr2_msgs.msg.AccessPoint()
00143 if self.access_point_valid is None:
00144 self.access_point_valid = False
00145 else:
00146 self.motors_halted = std_msgs.msg.Bool()
00147 self.motors_halted_valid = False
00148 self.power_board_state = pr2_msgs.msg.PowerBoardState()
00149 self.power_board_state_valid = False
00150 self.power_state = pr2_msgs.msg.PowerState()
00151 self.power_state_valid = False
00152 self.access_point = pr2_msgs.msg.AccessPoint()
00153 self.access_point_valid = False
00154
00155 def _get_types(self):
00156 """
00157 internal API method
00158 """
00159 return self._slot_types
00160
00161 def serialize(self, buff):
00162 """
00163 serialize message into buffer
00164 :param buff: buffer, ``StringIO``
00165 """
00166 try:
00167 _x = self
00168 buff.write(_struct_2B3I.pack(_x.motors_halted.data, _x.motors_halted_valid, _x.power_board_state.header.seq, _x.power_board_state.header.stamp.secs, _x.power_board_state.header.stamp.nsecs))
00169 _x = self.power_board_state.header.frame_id
00170 length = len(_x)
00171 if python3 or type(_x) == unicode:
00172 _x = _x.encode('utf-8')
00173 length = len(_x)
00174 buff.write(struct.pack('<I%ss'%length, length, _x))
00175 _x = self.power_board_state.name
00176 length = len(_x)
00177 if python3 or type(_x) == unicode:
00178 _x = _x.encode('utf-8')
00179 length = len(_x)
00180 buff.write(struct.pack('<I%ss'%length, length, _x))
00181 _x = self
00182 buff.write(_struct_Idb.pack(_x.power_board_state.serial_num, _x.power_board_state.input_voltage, _x.power_board_state.master_state))
00183 buff.write(_struct_3b.pack(*self.power_board_state.circuit_state))
00184 buff.write(_struct_3d.pack(*self.power_board_state.circuit_voltage))
00185 _x = self
00186 buff.write(_struct_3B3I.pack(_x.power_board_state.run_stop, _x.power_board_state.wireless_stop, _x.power_board_state_valid, _x.power_state.header.seq, _x.power_state.header.stamp.secs, _x.power_state.header.stamp.nsecs))
00187 _x = self.power_state.header.frame_id
00188 length = len(_x)
00189 if python3 or type(_x) == unicode:
00190 _x = _x.encode('utf-8')
00191 length = len(_x)
00192 buff.write(struct.pack('<I%ss'%length, length, _x))
00193 _x = self
00194 buff.write(_struct_d2i.pack(_x.power_state.power_consumption, _x.power_state.time_remaining.secs, _x.power_state.time_remaining.nsecs))
00195 _x = self.power_state.prediction_method
00196 length = len(_x)
00197 if python3 or type(_x) == unicode:
00198 _x = _x.encode('utf-8')
00199 length = len(_x)
00200 buff.write(struct.pack('<I%ss'%length, length, _x))
00201 _x = self
00202 buff.write(_struct_2bB3I.pack(_x.power_state.relative_capacity, _x.power_state.AC_present, _x.power_state_valid, _x.access_point.header.seq, _x.access_point.header.stamp.secs, _x.access_point.header.stamp.nsecs))
00203 _x = self.access_point.header.frame_id
00204 length = len(_x)
00205 if python3 or type(_x) == unicode:
00206 _x = _x.encode('utf-8')
00207 length = len(_x)
00208 buff.write(struct.pack('<I%ss'%length, length, _x))
00209 _x = self.access_point.essid
00210 length = len(_x)
00211 if python3 or type(_x) == unicode:
00212 _x = _x.encode('utf-8')
00213 length = len(_x)
00214 buff.write(struct.pack('<I%ss'%length, length, _x))
00215 _x = self.access_point.macaddr
00216 length = len(_x)
00217 if python3 or type(_x) == unicode:
00218 _x = _x.encode('utf-8')
00219 length = len(_x)
00220 buff.write(struct.pack('<I%ss'%length, length, _x))
00221 _x = self
00222 buff.write(_struct_4i.pack(_x.access_point.signal, _x.access_point.noise, _x.access_point.snr, _x.access_point.channel))
00223 _x = self.access_point.rate
00224 length = len(_x)
00225 if python3 or type(_x) == unicode:
00226 _x = _x.encode('utf-8')
00227 length = len(_x)
00228 buff.write(struct.pack('<I%ss'%length, length, _x))
00229 _x = self.access_point.tx_power
00230 length = len(_x)
00231 if python3 or type(_x) == unicode:
00232 _x = _x.encode('utf-8')
00233 length = len(_x)
00234 buff.write(struct.pack('<I%ss'%length, length, _x))
00235 _x = self
00236 buff.write(_struct_iB.pack(_x.access_point.quality, _x.access_point_valid))
00237 except struct.error as se: self._check_types(se)
00238 except TypeError as te: self._check_types(te)
00239
00240 def deserialize(self, str):
00241 """
00242 unpack serialized message in str into this message instance
00243 :param str: byte array of serialized message, ``str``
00244 """
00245 try:
00246 if self.motors_halted is None:
00247 self.motors_halted = std_msgs.msg.Bool()
00248 if self.power_board_state is None:
00249 self.power_board_state = pr2_msgs.msg.PowerBoardState()
00250 if self.power_state is None:
00251 self.power_state = pr2_msgs.msg.PowerState()
00252 if self.access_point is None:
00253 self.access_point = pr2_msgs.msg.AccessPoint()
00254 end = 0
00255 _x = self
00256 start = end
00257 end += 14
00258 (_x.motors_halted.data, _x.motors_halted_valid, _x.power_board_state.header.seq, _x.power_board_state.header.stamp.secs, _x.power_board_state.header.stamp.nsecs,) = _struct_2B3I.unpack(str[start:end])
00259 self.motors_halted.data = bool(self.motors_halted.data)
00260 self.motors_halted_valid = bool(self.motors_halted_valid)
00261 start = end
00262 end += 4
00263 (length,) = _struct_I.unpack(str[start:end])
00264 start = end
00265 end += length
00266 if python3:
00267 self.power_board_state.header.frame_id = str[start:end].decode('utf-8')
00268 else:
00269 self.power_board_state.header.frame_id = str[start:end]
00270 start = end
00271 end += 4
00272 (length,) = _struct_I.unpack(str[start:end])
00273 start = end
00274 end += length
00275 if python3:
00276 self.power_board_state.name = str[start:end].decode('utf-8')
00277 else:
00278 self.power_board_state.name = str[start:end]
00279 _x = self
00280 start = end
00281 end += 13
00282 (_x.power_board_state.serial_num, _x.power_board_state.input_voltage, _x.power_board_state.master_state,) = _struct_Idb.unpack(str[start:end])
00283 start = end
00284 end += 3
00285 self.power_board_state.circuit_state = _struct_3b.unpack(str[start:end])
00286 start = end
00287 end += 24
00288 self.power_board_state.circuit_voltage = _struct_3d.unpack(str[start:end])
00289 _x = self
00290 start = end
00291 end += 15
00292 (_x.power_board_state.run_stop, _x.power_board_state.wireless_stop, _x.power_board_state_valid, _x.power_state.header.seq, _x.power_state.header.stamp.secs, _x.power_state.header.stamp.nsecs,) = _struct_3B3I.unpack(str[start:end])
00293 self.power_board_state.run_stop = bool(self.power_board_state.run_stop)
00294 self.power_board_state.wireless_stop = bool(self.power_board_state.wireless_stop)
00295 self.power_board_state_valid = bool(self.power_board_state_valid)
00296 start = end
00297 end += 4
00298 (length,) = _struct_I.unpack(str[start:end])
00299 start = end
00300 end += length
00301 if python3:
00302 self.power_state.header.frame_id = str[start:end].decode('utf-8')
00303 else:
00304 self.power_state.header.frame_id = str[start:end]
00305 _x = self
00306 start = end
00307 end += 16
00308 (_x.power_state.power_consumption, _x.power_state.time_remaining.secs, _x.power_state.time_remaining.nsecs,) = _struct_d2i.unpack(str[start:end])
00309 start = end
00310 end += 4
00311 (length,) = _struct_I.unpack(str[start:end])
00312 start = end
00313 end += length
00314 if python3:
00315 self.power_state.prediction_method = str[start:end].decode('utf-8')
00316 else:
00317 self.power_state.prediction_method = str[start:end]
00318 _x = self
00319 start = end
00320 end += 15
00321 (_x.power_state.relative_capacity, _x.power_state.AC_present, _x.power_state_valid, _x.access_point.header.seq, _x.access_point.header.stamp.secs, _x.access_point.header.stamp.nsecs,) = _struct_2bB3I.unpack(str[start:end])
00322 self.power_state_valid = bool(self.power_state_valid)
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 start = end
00327 end += length
00328 if python3:
00329 self.access_point.header.frame_id = str[start:end].decode('utf-8')
00330 else:
00331 self.access_point.header.frame_id = str[start:end]
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 start = end
00336 end += length
00337 if python3:
00338 self.access_point.essid = str[start:end].decode('utf-8')
00339 else:
00340 self.access_point.essid = str[start:end]
00341 start = end
00342 end += 4
00343 (length,) = _struct_I.unpack(str[start:end])
00344 start = end
00345 end += length
00346 if python3:
00347 self.access_point.macaddr = str[start:end].decode('utf-8')
00348 else:
00349 self.access_point.macaddr = str[start:end]
00350 _x = self
00351 start = end
00352 end += 16
00353 (_x.access_point.signal, _x.access_point.noise, _x.access_point.snr, _x.access_point.channel,) = _struct_4i.unpack(str[start:end])
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 start = end
00358 end += length
00359 if python3:
00360 self.access_point.rate = str[start:end].decode('utf-8')
00361 else:
00362 self.access_point.rate = str[start:end]
00363 start = end
00364 end += 4
00365 (length,) = _struct_I.unpack(str[start:end])
00366 start = end
00367 end += length
00368 if python3:
00369 self.access_point.tx_power = str[start:end].decode('utf-8')
00370 else:
00371 self.access_point.tx_power = str[start:end]
00372 _x = self
00373 start = end
00374 end += 5
00375 (_x.access_point.quality, _x.access_point_valid,) = _struct_iB.unpack(str[start:end])
00376 self.access_point_valid = bool(self.access_point_valid)
00377 return self
00378 except struct.error as e:
00379 raise genpy.DeserializationError(e)
00380
00381
00382 def serialize_numpy(self, buff, numpy):
00383 """
00384 serialize message with numpy array types into buffer
00385 :param buff: buffer, ``StringIO``
00386 :param numpy: numpy python module
00387 """
00388 try:
00389 _x = self
00390 buff.write(_struct_2B3I.pack(_x.motors_halted.data, _x.motors_halted_valid, _x.power_board_state.header.seq, _x.power_board_state.header.stamp.secs, _x.power_board_state.header.stamp.nsecs))
00391 _x = self.power_board_state.header.frame_id
00392 length = len(_x)
00393 if python3 or type(_x) == unicode:
00394 _x = _x.encode('utf-8')
00395 length = len(_x)
00396 buff.write(struct.pack('<I%ss'%length, length, _x))
00397 _x = self.power_board_state.name
00398 length = len(_x)
00399 if python3 or type(_x) == unicode:
00400 _x = _x.encode('utf-8')
00401 length = len(_x)
00402 buff.write(struct.pack('<I%ss'%length, length, _x))
00403 _x = self
00404 buff.write(_struct_Idb.pack(_x.power_board_state.serial_num, _x.power_board_state.input_voltage, _x.power_board_state.master_state))
00405 buff.write(self.power_board_state.circuit_state.tostring())
00406 buff.write(self.power_board_state.circuit_voltage.tostring())
00407 _x = self
00408 buff.write(_struct_3B3I.pack(_x.power_board_state.run_stop, _x.power_board_state.wireless_stop, _x.power_board_state_valid, _x.power_state.header.seq, _x.power_state.header.stamp.secs, _x.power_state.header.stamp.nsecs))
00409 _x = self.power_state.header.frame_id
00410 length = len(_x)
00411 if python3 or type(_x) == unicode:
00412 _x = _x.encode('utf-8')
00413 length = len(_x)
00414 buff.write(struct.pack('<I%ss'%length, length, _x))
00415 _x = self
00416 buff.write(_struct_d2i.pack(_x.power_state.power_consumption, _x.power_state.time_remaining.secs, _x.power_state.time_remaining.nsecs))
00417 _x = self.power_state.prediction_method
00418 length = len(_x)
00419 if python3 or type(_x) == unicode:
00420 _x = _x.encode('utf-8')
00421 length = len(_x)
00422 buff.write(struct.pack('<I%ss'%length, length, _x))
00423 _x = self
00424 buff.write(_struct_2bB3I.pack(_x.power_state.relative_capacity, _x.power_state.AC_present, _x.power_state_valid, _x.access_point.header.seq, _x.access_point.header.stamp.secs, _x.access_point.header.stamp.nsecs))
00425 _x = self.access_point.header.frame_id
00426 length = len(_x)
00427 if python3 or type(_x) == unicode:
00428 _x = _x.encode('utf-8')
00429 length = len(_x)
00430 buff.write(struct.pack('<I%ss'%length, length, _x))
00431 _x = self.access_point.essid
00432 length = len(_x)
00433 if python3 or type(_x) == unicode:
00434 _x = _x.encode('utf-8')
00435 length = len(_x)
00436 buff.write(struct.pack('<I%ss'%length, length, _x))
00437 _x = self.access_point.macaddr
00438 length = len(_x)
00439 if python3 or type(_x) == unicode:
00440 _x = _x.encode('utf-8')
00441 length = len(_x)
00442 buff.write(struct.pack('<I%ss'%length, length, _x))
00443 _x = self
00444 buff.write(_struct_4i.pack(_x.access_point.signal, _x.access_point.noise, _x.access_point.snr, _x.access_point.channel))
00445 _x = self.access_point.rate
00446 length = len(_x)
00447 if python3 or type(_x) == unicode:
00448 _x = _x.encode('utf-8')
00449 length = len(_x)
00450 buff.write(struct.pack('<I%ss'%length, length, _x))
00451 _x = self.access_point.tx_power
00452 length = len(_x)
00453 if python3 or type(_x) == unicode:
00454 _x = _x.encode('utf-8')
00455 length = len(_x)
00456 buff.write(struct.pack('<I%ss'%length, length, _x))
00457 _x = self
00458 buff.write(_struct_iB.pack(_x.access_point.quality, _x.access_point_valid))
00459 except struct.error as se: self._check_types(se)
00460 except TypeError as te: self._check_types(te)
00461
00462 def deserialize_numpy(self, str, numpy):
00463 """
00464 unpack serialized message in str into this message instance using numpy for array types
00465 :param str: byte array of serialized message, ``str``
00466 :param numpy: numpy python module
00467 """
00468 try:
00469 if self.motors_halted is None:
00470 self.motors_halted = std_msgs.msg.Bool()
00471 if self.power_board_state is None:
00472 self.power_board_state = pr2_msgs.msg.PowerBoardState()
00473 if self.power_state is None:
00474 self.power_state = pr2_msgs.msg.PowerState()
00475 if self.access_point is None:
00476 self.access_point = pr2_msgs.msg.AccessPoint()
00477 end = 0
00478 _x = self
00479 start = end
00480 end += 14
00481 (_x.motors_halted.data, _x.motors_halted_valid, _x.power_board_state.header.seq, _x.power_board_state.header.stamp.secs, _x.power_board_state.header.stamp.nsecs,) = _struct_2B3I.unpack(str[start:end])
00482 self.motors_halted.data = bool(self.motors_halted.data)
00483 self.motors_halted_valid = bool(self.motors_halted_valid)
00484 start = end
00485 end += 4
00486 (length,) = _struct_I.unpack(str[start:end])
00487 start = end
00488 end += length
00489 if python3:
00490 self.power_board_state.header.frame_id = str[start:end].decode('utf-8')
00491 else:
00492 self.power_board_state.header.frame_id = str[start:end]
00493 start = end
00494 end += 4
00495 (length,) = _struct_I.unpack(str[start:end])
00496 start = end
00497 end += length
00498 if python3:
00499 self.power_board_state.name = str[start:end].decode('utf-8')
00500 else:
00501 self.power_board_state.name = str[start:end]
00502 _x = self
00503 start = end
00504 end += 13
00505 (_x.power_board_state.serial_num, _x.power_board_state.input_voltage, _x.power_board_state.master_state,) = _struct_Idb.unpack(str[start:end])
00506 start = end
00507 end += 3
00508 self.power_board_state.circuit_state = numpy.frombuffer(str[start:end], dtype=numpy.int8, count=3)
00509 start = end
00510 end += 24
00511 self.power_board_state.circuit_voltage = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=3)
00512 _x = self
00513 start = end
00514 end += 15
00515 (_x.power_board_state.run_stop, _x.power_board_state.wireless_stop, _x.power_board_state_valid, _x.power_state.header.seq, _x.power_state.header.stamp.secs, _x.power_state.header.stamp.nsecs,) = _struct_3B3I.unpack(str[start:end])
00516 self.power_board_state.run_stop = bool(self.power_board_state.run_stop)
00517 self.power_board_state.wireless_stop = bool(self.power_board_state.wireless_stop)
00518 self.power_board_state_valid = bool(self.power_board_state_valid)
00519 start = end
00520 end += 4
00521 (length,) = _struct_I.unpack(str[start:end])
00522 start = end
00523 end += length
00524 if python3:
00525 self.power_state.header.frame_id = str[start:end].decode('utf-8')
00526 else:
00527 self.power_state.header.frame_id = str[start:end]
00528 _x = self
00529 start = end
00530 end += 16
00531 (_x.power_state.power_consumption, _x.power_state.time_remaining.secs, _x.power_state.time_remaining.nsecs,) = _struct_d2i.unpack(str[start:end])
00532 start = end
00533 end += 4
00534 (length,) = _struct_I.unpack(str[start:end])
00535 start = end
00536 end += length
00537 if python3:
00538 self.power_state.prediction_method = str[start:end].decode('utf-8')
00539 else:
00540 self.power_state.prediction_method = str[start:end]
00541 _x = self
00542 start = end
00543 end += 15
00544 (_x.power_state.relative_capacity, _x.power_state.AC_present, _x.power_state_valid, _x.access_point.header.seq, _x.access_point.header.stamp.secs, _x.access_point.header.stamp.nsecs,) = _struct_2bB3I.unpack(str[start:end])
00545 self.power_state_valid = bool(self.power_state_valid)
00546 start = end
00547 end += 4
00548 (length,) = _struct_I.unpack(str[start:end])
00549 start = end
00550 end += length
00551 if python3:
00552 self.access_point.header.frame_id = str[start:end].decode('utf-8')
00553 else:
00554 self.access_point.header.frame_id = str[start:end]
00555 start = end
00556 end += 4
00557 (length,) = _struct_I.unpack(str[start:end])
00558 start = end
00559 end += length
00560 if python3:
00561 self.access_point.essid = str[start:end].decode('utf-8')
00562 else:
00563 self.access_point.essid = str[start:end]
00564 start = end
00565 end += 4
00566 (length,) = _struct_I.unpack(str[start:end])
00567 start = end
00568 end += length
00569 if python3:
00570 self.access_point.macaddr = str[start:end].decode('utf-8')
00571 else:
00572 self.access_point.macaddr = str[start:end]
00573 _x = self
00574 start = end
00575 end += 16
00576 (_x.access_point.signal, _x.access_point.noise, _x.access_point.snr, _x.access_point.channel,) = _struct_4i.unpack(str[start:end])
00577 start = end
00578 end += 4
00579 (length,) = _struct_I.unpack(str[start:end])
00580 start = end
00581 end += length
00582 if python3:
00583 self.access_point.rate = str[start:end].decode('utf-8')
00584 else:
00585 self.access_point.rate = str[start:end]
00586 start = end
00587 end += 4
00588 (length,) = _struct_I.unpack(str[start:end])
00589 start = end
00590 end += length
00591 if python3:
00592 self.access_point.tx_power = str[start:end].decode('utf-8')
00593 else:
00594 self.access_point.tx_power = str[start:end]
00595 _x = self
00596 start = end
00597 end += 5
00598 (_x.access_point.quality, _x.access_point_valid,) = _struct_iB.unpack(str[start:end])
00599 self.access_point_valid = bool(self.access_point_valid)
00600 return self
00601 except struct.error as e:
00602 raise genpy.DeserializationError(e)
00603
00604 _struct_I = genpy.struct_I
00605 _struct_2B3I = struct.Struct("<2B3I")
00606 _struct_4i = struct.Struct("<4i")
00607 _struct_3B3I = struct.Struct("<3B3I")
00608 _struct_d2i = struct.Struct("<d2i")
00609 _struct_2bB3I = struct.Struct("<2bB3I")
00610 _struct_3b = struct.Struct("<3b")
00611 _struct_iB = struct.Struct("<iB")
00612 _struct_Idb = struct.Struct("<Idb")
00613 _struct_3d = struct.Struct("<3d")