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