_PowerBoardState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_msgs/PowerBoardState.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 std_msgs.msg
00008 
00009 class PowerBoardState(genpy.Message):
00010   _md5sum = "08899b671e6a1a449e7ce0000da8ae7b"
00011   _type = "pr2_msgs/PowerBoardState"
00012   _has_header = True #flag to mark the presence of a Header object
00013   _full_text = """# This message communicates the state of the PR2's power board.
00014 int8 STATE_NOPOWER=0
00015 int8 STATE_STANDBY=1
00016 int8 STATE_PUMPING=2
00017 int8 STATE_ON=3
00018 int8 STATE_ENABLED=3  # Preferred over STATE_ON, keeping STATE_ON for backcompat
00019 int8 STATE_DISABLED=4
00020 
00021 int8 MASTER_NOPOWER=0
00022 int8 MASTER_STANDBY=1
00023 int8 MASTER_ON=2
00024 int8 MASTER_OFF=3
00025 int8 MASTER_SHUTDOWN=4
00026 
00027 Header header
00028 string name # Name with serial number
00029 uint32 serial_num # Serial number for this board's message
00030 float64 input_voltage # Input voltage to power board
00031 
00032 # Master States:
00033 #  MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN 
00034 int8 master_state  # The master state machine's state in the powerboard
00035 
00036 # Circuit States:
00037 #  STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED
00038 int8[3] circuit_state # One of the above states
00039 float64[3] circuit_voltage  # Output voltage of each circuit
00040 
00041 # True if robot should be enabled
00042 bool run_stop           #Note - if the wireless run-stop is hit, this will be unobservable
00043 bool wireless_stop 
00044 
00045 ================================================================================
00046 MSG: std_msgs/Header
00047 # Standard metadata for higher-level stamped data types.
00048 # This is generally used to communicate timestamped data 
00049 # in a particular coordinate frame.
00050 # 
00051 # sequence ID: consecutively increasing ID 
00052 uint32 seq
00053 #Two-integer timestamp that is expressed as:
00054 # * stamp.secs: seconds (stamp_secs) since epoch
00055 # * stamp.nsecs: nanoseconds since stamp_secs
00056 # time-handling sugar is provided by the client library
00057 time stamp
00058 #Frame this data is associated with
00059 # 0: no frame
00060 # 1: global frame
00061 string frame_id
00062 
00063 """
00064   # Pseudo-constants
00065   STATE_NOPOWER = 0
00066   STATE_STANDBY = 1
00067   STATE_PUMPING = 2
00068   STATE_ON = 3
00069   STATE_ENABLED = 3
00070   STATE_DISABLED = 4
00071   MASTER_NOPOWER = 0
00072   MASTER_STANDBY = 1
00073   MASTER_ON = 2
00074   MASTER_OFF = 3
00075   MASTER_SHUTDOWN = 4
00076 
00077   __slots__ = ['header','name','serial_num','input_voltage','master_state','circuit_state','circuit_voltage','run_stop','wireless_stop']
00078   _slot_types = ['std_msgs/Header','string','uint32','float64','int8','int8[3]','float64[3]','bool','bool']
00079 
00080   def __init__(self, *args, **kwds):
00081     """
00082     Constructor. Any message fields that are implicitly/explicitly
00083     set to None will be assigned a default value. The recommend
00084     use is keyword arguments as this is more robust to future message
00085     changes.  You cannot mix in-order arguments and keyword arguments.
00086 
00087     The available fields are:
00088        header,name,serial_num,input_voltage,master_state,circuit_state,circuit_voltage,run_stop,wireless_stop
00089 
00090     :param args: complete set of field values, in .msg order
00091     :param kwds: use keyword arguments corresponding to message field names
00092     to set specific fields.
00093     """
00094     if args or kwds:
00095       super(PowerBoardState, self).__init__(*args, **kwds)
00096       #message fields cannot be None, assign default values for those that are
00097       if self.header is None:
00098         self.header = std_msgs.msg.Header()
00099       if self.name is None:
00100         self.name = ''
00101       if self.serial_num is None:
00102         self.serial_num = 0
00103       if self.input_voltage is None:
00104         self.input_voltage = 0.
00105       if self.master_state is None:
00106         self.master_state = 0
00107       if self.circuit_state is None:
00108         self.circuit_state = [0,0,0]
00109       if self.circuit_voltage is None:
00110         self.circuit_voltage = [0.,0.,0.]
00111       if self.run_stop is None:
00112         self.run_stop = False
00113       if self.wireless_stop is None:
00114         self.wireless_stop = False
00115     else:
00116       self.header = std_msgs.msg.Header()
00117       self.name = ''
00118       self.serial_num = 0
00119       self.input_voltage = 0.
00120       self.master_state = 0
00121       self.circuit_state = [0,0,0]
00122       self.circuit_voltage = [0.,0.,0.]
00123       self.run_stop = False
00124       self.wireless_stop = False
00125 
00126   def _get_types(self):
00127     """
00128     internal API method
00129     """
00130     return self._slot_types
00131 
00132   def serialize(self, buff):
00133     """
00134     serialize message into buffer
00135     :param buff: buffer, ``StringIO``
00136     """
00137     try:
00138       _x = self
00139       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00140       _x = self.header.frame_id
00141       length = len(_x)
00142       if python3 or type(_x) == unicode:
00143         _x = _x.encode('utf-8')
00144         length = len(_x)
00145       buff.write(struct.pack('<I%ss'%length, length, _x))
00146       _x = self.name
00147       length = len(_x)
00148       if python3 or type(_x) == unicode:
00149         _x = _x.encode('utf-8')
00150         length = len(_x)
00151       buff.write(struct.pack('<I%ss'%length, length, _x))
00152       _x = self
00153       buff.write(_struct_Idb.pack(_x.serial_num, _x.input_voltage, _x.master_state))
00154       buff.write(_struct_3b.pack(*self.circuit_state))
00155       buff.write(_struct_3d.pack(*self.circuit_voltage))
00156       _x = self
00157       buff.write(_struct_2B.pack(_x.run_stop, _x.wireless_stop))
00158     except struct.error as se: self._check_types(se)
00159     except TypeError as te: self._check_types(te)
00160 
00161   def deserialize(self, str):
00162     """
00163     unpack serialized message in str into this message instance
00164     :param str: byte array of serialized message, ``str``
00165     """
00166     try:
00167       if self.header is None:
00168         self.header = std_msgs.msg.Header()
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       if python3:
00180         self.header.frame_id = str[start:end].decode('utf-8')
00181       else:
00182         self.header.frame_id = str[start:end]
00183       start = end
00184       end += 4
00185       (length,) = _struct_I.unpack(str[start:end])
00186       start = end
00187       end += length
00188       if python3:
00189         self.name = str[start:end].decode('utf-8')
00190       else:
00191         self.name = str[start:end]
00192       _x = self
00193       start = end
00194       end += 13
00195       (_x.serial_num, _x.input_voltage, _x.master_state,) = _struct_Idb.unpack(str[start:end])
00196       start = end
00197       end += 3
00198       self.circuit_state = _struct_3b.unpack(str[start:end])
00199       start = end
00200       end += 24
00201       self.circuit_voltage = _struct_3d.unpack(str[start:end])
00202       _x = self
00203       start = end
00204       end += 2
00205       (_x.run_stop, _x.wireless_stop,) = _struct_2B.unpack(str[start:end])
00206       self.run_stop = bool(self.run_stop)
00207       self.wireless_stop = bool(self.wireless_stop)
00208       return self
00209     except struct.error as e:
00210       raise genpy.DeserializationError(e) #most likely buffer underfill
00211 
00212 
00213   def serialize_numpy(self, buff, numpy):
00214     """
00215     serialize message with numpy array types into buffer
00216     :param buff: buffer, ``StringIO``
00217     :param numpy: numpy python module
00218     """
00219     try:
00220       _x = self
00221       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00222       _x = self.header.frame_id
00223       length = len(_x)
00224       if python3 or type(_x) == unicode:
00225         _x = _x.encode('utf-8')
00226         length = len(_x)
00227       buff.write(struct.pack('<I%ss'%length, length, _x))
00228       _x = self.name
00229       length = len(_x)
00230       if python3 or type(_x) == unicode:
00231         _x = _x.encode('utf-8')
00232         length = len(_x)
00233       buff.write(struct.pack('<I%ss'%length, length, _x))
00234       _x = self
00235       buff.write(_struct_Idb.pack(_x.serial_num, _x.input_voltage, _x.master_state))
00236       buff.write(self.circuit_state.tostring())
00237       buff.write(self.circuit_voltage.tostring())
00238       _x = self
00239       buff.write(_struct_2B.pack(_x.run_stop, _x.wireless_stop))
00240     except struct.error as se: self._check_types(se)
00241     except TypeError as te: self._check_types(te)
00242 
00243   def deserialize_numpy(self, str, numpy):
00244     """
00245     unpack serialized message in str into this message instance using numpy for array types
00246     :param str: byte array of serialized message, ``str``
00247     :param numpy: numpy python module
00248     """
00249     try:
00250       if self.header is None:
00251         self.header = std_msgs.msg.Header()
00252       end = 0
00253       _x = self
00254       start = end
00255       end += 12
00256       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00257       start = end
00258       end += 4
00259       (length,) = _struct_I.unpack(str[start:end])
00260       start = end
00261       end += length
00262       if python3:
00263         self.header.frame_id = str[start:end].decode('utf-8')
00264       else:
00265         self.header.frame_id = str[start:end]
00266       start = end
00267       end += 4
00268       (length,) = _struct_I.unpack(str[start:end])
00269       start = end
00270       end += length
00271       if python3:
00272         self.name = str[start:end].decode('utf-8')
00273       else:
00274         self.name = str[start:end]
00275       _x = self
00276       start = end
00277       end += 13
00278       (_x.serial_num, _x.input_voltage, _x.master_state,) = _struct_Idb.unpack(str[start:end])
00279       start = end
00280       end += 3
00281       self.circuit_state = numpy.frombuffer(str[start:end], dtype=numpy.int8, count=3)
00282       start = end
00283       end += 24
00284       self.circuit_voltage = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=3)
00285       _x = self
00286       start = end
00287       end += 2
00288       (_x.run_stop, _x.wireless_stop,) = _struct_2B.unpack(str[start:end])
00289       self.run_stop = bool(self.run_stop)
00290       self.wireless_stop = bool(self.wireless_stop)
00291       return self
00292     except struct.error as e:
00293       raise genpy.DeserializationError(e) #most likely buffer underfill
00294 
00295 _struct_I = genpy.struct_I
00296 _struct_3b = struct.Struct("<3b")
00297 _struct_3I = struct.Struct("<3I")
00298 _struct_Idb = struct.Struct("<Idb")
00299 _struct_2B = struct.Struct("<2B")
00300 _struct_3d = struct.Struct("<3d")


pr2_msgs
Author(s): Eric Berger and many others
autogenerated on Mon Jan 6 2014 11:34:07