_SensorState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from kobuki_comms/SensorState.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 SensorState(genpy.Message):
00010   _md5sum = "98cbcd372761832ea3a9c795bb69a09f"
00011   _type = "kobuki_comms/SensorState"
00012   _has_header = True #flag to mark the presence of a Header object
00013   _full_text = """# Kobuki Sensor Data Messages
00014 #
00015 
00016 # Buttons bitmasks to decode byte "buttons"
00017 uint8 Button0 = 1  # 0x02
00018 uint8 Button1 = 2  # 0x01
00019 uint8 Button2 = 4  # 0x04
00020 
00021 # Byte "charger" format:
00022 # - first four bits distinguish between adapter or docking base charging
00023 uint8 ADAPTER     = 16 # bitmask 0x10
00024 # - last 4 bits specified the charging status
00025 uint8 DISCHARGING = 0
00026 uint8 CHARGED     = 2
00027 uint8 CHARGING    = 6
00028 
00029 
00030 Header header
00031 
00032 ###################
00033 # Core Packet
00034 ###################
00035 uint16 time_stamp
00036 uint8  bumper
00037 uint8  wheel_drop
00038 uint8  cliff
00039 uint16 left_encoder
00040 uint16 right_encoder
00041 int8  left_pwm
00042 int8  right_pwm
00043 uint8  buttons
00044 uint8  charger
00045 uint8  battery
00046 
00047 ###################
00048 # Cliff Packet
00049 ###################
00050 uint16[] bottom
00051 
00052 ###################
00053 # Current Packet
00054 ###################
00055 uint8[] current
00056 
00057 ###################
00058 # GP Input Packet
00059 ###################
00060 uint16 digital_input
00061 uint16[] analog_input
00062 
00063 ================================================================================
00064 MSG: std_msgs/Header
00065 # Standard metadata for higher-level stamped data types.
00066 # This is generally used to communicate timestamped data 
00067 # in a particular coordinate frame.
00068 # 
00069 # sequence ID: consecutively increasing ID 
00070 uint32 seq
00071 #Two-integer timestamp that is expressed as:
00072 # * stamp.secs: seconds (stamp_secs) since epoch
00073 # * stamp.nsecs: nanoseconds since stamp_secs
00074 # time-handling sugar is provided by the client library
00075 time stamp
00076 #Frame this data is associated with
00077 # 0: no frame
00078 # 1: global frame
00079 string frame_id
00080 
00081 """
00082   # Pseudo-constants
00083   Button0 = 1
00084   Button1 = 2
00085   Button2 = 4
00086   ADAPTER = 16
00087   DISCHARGING = 0
00088   CHARGED = 2
00089   CHARGING = 6
00090 
00091   __slots__ = ['header','time_stamp','bumper','wheel_drop','cliff','left_encoder','right_encoder','left_pwm','right_pwm','buttons','charger','battery','bottom','current','digital_input','analog_input']
00092   _slot_types = ['std_msgs/Header','uint16','uint8','uint8','uint8','uint16','uint16','int8','int8','uint8','uint8','uint8','uint16[]','uint8[]','uint16','uint16[]']
00093 
00094   def __init__(self, *args, **kwds):
00095     """
00096     Constructor. Any message fields that are implicitly/explicitly
00097     set to None will be assigned a default value. The recommend
00098     use is keyword arguments as this is more robust to future message
00099     changes.  You cannot mix in-order arguments and keyword arguments.
00100 
00101     The available fields are:
00102        header,time_stamp,bumper,wheel_drop,cliff,left_encoder,right_encoder,left_pwm,right_pwm,buttons,charger,battery,bottom,current,digital_input,analog_input
00103 
00104     :param args: complete set of field values, in .msg order
00105     :param kwds: use keyword arguments corresponding to message field names
00106     to set specific fields.
00107     """
00108     if args or kwds:
00109       super(SensorState, self).__init__(*args, **kwds)
00110       #message fields cannot be None, assign default values for those that are
00111       if self.header is None:
00112         self.header = std_msgs.msg.Header()
00113       if self.time_stamp is None:
00114         self.time_stamp = 0
00115       if self.bumper is None:
00116         self.bumper = 0
00117       if self.wheel_drop is None:
00118         self.wheel_drop = 0
00119       if self.cliff is None:
00120         self.cliff = 0
00121       if self.left_encoder is None:
00122         self.left_encoder = 0
00123       if self.right_encoder is None:
00124         self.right_encoder = 0
00125       if self.left_pwm is None:
00126         self.left_pwm = 0
00127       if self.right_pwm is None:
00128         self.right_pwm = 0
00129       if self.buttons is None:
00130         self.buttons = 0
00131       if self.charger is None:
00132         self.charger = 0
00133       if self.battery is None:
00134         self.battery = 0
00135       if self.bottom is None:
00136         self.bottom = []
00137       if self.current is None:
00138         self.current = ''
00139       if self.digital_input is None:
00140         self.digital_input = 0
00141       if self.analog_input is None:
00142         self.analog_input = []
00143     else:
00144       self.header = std_msgs.msg.Header()
00145       self.time_stamp = 0
00146       self.bumper = 0
00147       self.wheel_drop = 0
00148       self.cliff = 0
00149       self.left_encoder = 0
00150       self.right_encoder = 0
00151       self.left_pwm = 0
00152       self.right_pwm = 0
00153       self.buttons = 0
00154       self.charger = 0
00155       self.battery = 0
00156       self.bottom = []
00157       self.current = ''
00158       self.digital_input = 0
00159       self.analog_input = []
00160 
00161   def _get_types(self):
00162     """
00163     internal API method
00164     """
00165     return self._slot_types
00166 
00167   def serialize(self, buff):
00168     """
00169     serialize message into buffer
00170     :param buff: buffer, ``StringIO``
00171     """
00172     try:
00173       _x = self
00174       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00175       _x = self.header.frame_id
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_H3B2H2b3B.pack(_x.time_stamp, _x.bumper, _x.wheel_drop, _x.cliff, _x.left_encoder, _x.right_encoder, _x.left_pwm, _x.right_pwm, _x.buttons, _x.charger, _x.battery))
00183       length = len(self.bottom)
00184       buff.write(_struct_I.pack(length))
00185       pattern = '<%sH'%length
00186       buff.write(struct.pack(pattern, *self.bottom))
00187       _x = self.current
00188       length = len(_x)
00189       # - if encoded as a list instead, serialize as bytes instead of string
00190       if type(_x) in [list, tuple]:
00191         buff.write(struct.pack('<I%sB'%length, length, *_x))
00192       else:
00193         buff.write(struct.pack('<I%ss'%length, length, _x))
00194       buff.write(_struct_H.pack(self.digital_input))
00195       length = len(self.analog_input)
00196       buff.write(_struct_I.pack(length))
00197       pattern = '<%sH'%length
00198       buff.write(struct.pack(pattern, *self.analog_input))
00199     except struct.error as se: self._check_types(se)
00200     except TypeError as te: self._check_types(te)
00201 
00202   def deserialize(self, str):
00203     """
00204     unpack serialized message in str into this message instance
00205     :param str: byte array of serialized message, ``str``
00206     """
00207     try:
00208       if self.header is None:
00209         self.header = std_msgs.msg.Header()
00210       end = 0
00211       _x = self
00212       start = end
00213       end += 12
00214       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00215       start = end
00216       end += 4
00217       (length,) = _struct_I.unpack(str[start:end])
00218       start = end
00219       end += length
00220       if python3:
00221         self.header.frame_id = str[start:end].decode('utf-8')
00222       else:
00223         self.header.frame_id = str[start:end]
00224       _x = self
00225       start = end
00226       end += 14
00227       (_x.time_stamp, _x.bumper, _x.wheel_drop, _x.cliff, _x.left_encoder, _x.right_encoder, _x.left_pwm, _x.right_pwm, _x.buttons, _x.charger, _x.battery,) = _struct_H3B2H2b3B.unpack(str[start:end])
00228       start = end
00229       end += 4
00230       (length,) = _struct_I.unpack(str[start:end])
00231       pattern = '<%sH'%length
00232       start = end
00233       end += struct.calcsize(pattern)
00234       self.bottom = struct.unpack(pattern, str[start:end])
00235       start = end
00236       end += 4
00237       (length,) = _struct_I.unpack(str[start:end])
00238       start = end
00239       end += length
00240       if python3:
00241         self.current = str[start:end].decode('utf-8')
00242       else:
00243         self.current = str[start:end]
00244       start = end
00245       end += 2
00246       (self.digital_input,) = _struct_H.unpack(str[start:end])
00247       start = end
00248       end += 4
00249       (length,) = _struct_I.unpack(str[start:end])
00250       pattern = '<%sH'%length
00251       start = end
00252       end += struct.calcsize(pattern)
00253       self.analog_input = struct.unpack(pattern, str[start:end])
00254       return self
00255     except struct.error as e:
00256       raise genpy.DeserializationError(e) #most likely buffer underfill
00257 
00258 
00259   def serialize_numpy(self, buff, numpy):
00260     """
00261     serialize message with numpy array types into buffer
00262     :param buff: buffer, ``StringIO``
00263     :param numpy: numpy python module
00264     """
00265     try:
00266       _x = self
00267       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00268       _x = self.header.frame_id
00269       length = len(_x)
00270       if python3 or type(_x) == unicode:
00271         _x = _x.encode('utf-8')
00272         length = len(_x)
00273       buff.write(struct.pack('<I%ss'%length, length, _x))
00274       _x = self
00275       buff.write(_struct_H3B2H2b3B.pack(_x.time_stamp, _x.bumper, _x.wheel_drop, _x.cliff, _x.left_encoder, _x.right_encoder, _x.left_pwm, _x.right_pwm, _x.buttons, _x.charger, _x.battery))
00276       length = len(self.bottom)
00277       buff.write(_struct_I.pack(length))
00278       pattern = '<%sH'%length
00279       buff.write(self.bottom.tostring())
00280       _x = self.current
00281       length = len(_x)
00282       # - if encoded as a list instead, serialize as bytes instead of string
00283       if type(_x) in [list, tuple]:
00284         buff.write(struct.pack('<I%sB'%length, length, *_x))
00285       else:
00286         buff.write(struct.pack('<I%ss'%length, length, _x))
00287       buff.write(_struct_H.pack(self.digital_input))
00288       length = len(self.analog_input)
00289       buff.write(_struct_I.pack(length))
00290       pattern = '<%sH'%length
00291       buff.write(self.analog_input.tostring())
00292     except struct.error as se: self._check_types(se)
00293     except TypeError as te: self._check_types(te)
00294 
00295   def deserialize_numpy(self, str, numpy):
00296     """
00297     unpack serialized message in str into this message instance using numpy for array types
00298     :param str: byte array of serialized message, ``str``
00299     :param numpy: numpy python module
00300     """
00301     try:
00302       if self.header is None:
00303         self.header = std_msgs.msg.Header()
00304       end = 0
00305       _x = self
00306       start = end
00307       end += 12
00308       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.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.header.frame_id = str[start:end].decode('utf-8')
00316       else:
00317         self.header.frame_id = str[start:end]
00318       _x = self
00319       start = end
00320       end += 14
00321       (_x.time_stamp, _x.bumper, _x.wheel_drop, _x.cliff, _x.left_encoder, _x.right_encoder, _x.left_pwm, _x.right_pwm, _x.buttons, _x.charger, _x.battery,) = _struct_H3B2H2b3B.unpack(str[start:end])
00322       start = end
00323       end += 4
00324       (length,) = _struct_I.unpack(str[start:end])
00325       pattern = '<%sH'%length
00326       start = end
00327       end += struct.calcsize(pattern)
00328       self.bottom = numpy.frombuffer(str[start:end], dtype=numpy.uint16, count=length)
00329       start = end
00330       end += 4
00331       (length,) = _struct_I.unpack(str[start:end])
00332       start = end
00333       end += length
00334       if python3:
00335         self.current = str[start:end].decode('utf-8')
00336       else:
00337         self.current = str[start:end]
00338       start = end
00339       end += 2
00340       (self.digital_input,) = _struct_H.unpack(str[start:end])
00341       start = end
00342       end += 4
00343       (length,) = _struct_I.unpack(str[start:end])
00344       pattern = '<%sH'%length
00345       start = end
00346       end += struct.calcsize(pattern)
00347       self.analog_input = numpy.frombuffer(str[start:end], dtype=numpy.uint16, count=length)
00348       return self
00349     except struct.error as e:
00350       raise genpy.DeserializationError(e) #most likely buffer underfill
00351 
00352 _struct_I = genpy.struct_I
00353 _struct_H = struct.Struct("<H")
00354 _struct_3I = struct.Struct("<3I")
00355 _struct_H3B2H2b3B = struct.Struct("<H3B2H2b3B")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


kobuki_comms
Author(s): Daniel Stonier, 주영훈
autogenerated on Thu Nov 15 2012 18:05:16