00001 """autogenerated by genpy from irobot_create_2_1/SensorPacket.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 SensorPacket(genpy.Message):
00010 _md5sum = "56f92e8d70d283e7e15aa47855e73ea7"
00011 _type = "irobot_create_2_1/SensorPacket"
00012 _has_header = True
00013 _full_text = """Header header
00014 bool wheeldropCaster
00015 bool wheeldropLeft
00016 bool wheeldropRight
00017 bool bumpLeft
00018 bool bumpRight
00019 bool wall
00020 bool cliffLeft
00021 bool cliffFronLeft
00022 bool cliffFrontRight
00023 bool cliffRight
00024 bool virtualWall
00025 uint8 infraredByte
00026 bool advance
00027 bool play
00028 int16 distance
00029 int16 angle
00030 uint8 chargingState
00031 uint16 voltage
00032 int16 current
00033 int8 batteryTemperature
00034 uint16 batteryCharge
00035 uint16 batteryCapacity
00036 uint16 wallSignal
00037 uint16 cliffLeftSignal
00038 uint16 cliffFrontLeftSignal
00039 uint16 cliffFrontRightSignal
00040 uint16 cliffRightSignal
00041 bool homeBase
00042 bool internalCharger
00043 uint8 songNumber
00044 uint8 songPlaying
00045
00046 ================================================================================
00047 MSG: std_msgs/Header
00048 # Standard metadata for higher-level stamped data types.
00049 # This is generally used to communicate timestamped data
00050 # in a particular coordinate frame.
00051 #
00052 # sequence ID: consecutively increasing ID
00053 uint32 seq
00054 #Two-integer timestamp that is expressed as:
00055 # * stamp.secs: seconds (stamp_secs) since epoch
00056 # * stamp.nsecs: nanoseconds since stamp_secs
00057 # time-handling sugar is provided by the client library
00058 time stamp
00059 #Frame this data is associated with
00060 # 0: no frame
00061 # 1: global frame
00062 string frame_id
00063
00064 """
00065 __slots__ = ['header','wheeldropCaster','wheeldropLeft','wheeldropRight','bumpLeft','bumpRight','wall','cliffLeft','cliffFronLeft','cliffFrontRight','cliffRight','virtualWall','infraredByte','advance','play','distance','angle','chargingState','voltage','current','batteryTemperature','batteryCharge','batteryCapacity','wallSignal','cliffLeftSignal','cliffFrontLeftSignal','cliffFrontRightSignal','cliffRightSignal','homeBase','internalCharger','songNumber','songPlaying']
00066 _slot_types = ['std_msgs/Header','bool','bool','bool','bool','bool','bool','bool','bool','bool','bool','bool','uint8','bool','bool','int16','int16','uint8','uint16','int16','int8','uint16','uint16','uint16','uint16','uint16','uint16','uint16','bool','bool','uint8','uint8']
00067
00068 def __init__(self, *args, **kwds):
00069 """
00070 Constructor. Any message fields that are implicitly/explicitly
00071 set to None will be assigned a default value. The recommend
00072 use is keyword arguments as this is more robust to future message
00073 changes. You cannot mix in-order arguments and keyword arguments.
00074
00075 The available fields are:
00076 header,wheeldropCaster,wheeldropLeft,wheeldropRight,bumpLeft,bumpRight,wall,cliffLeft,cliffFronLeft,cliffFrontRight,cliffRight,virtualWall,infraredByte,advance,play,distance,angle,chargingState,voltage,current,batteryTemperature,batteryCharge,batteryCapacity,wallSignal,cliffLeftSignal,cliffFrontLeftSignal,cliffFrontRightSignal,cliffRightSignal,homeBase,internalCharger,songNumber,songPlaying
00077
00078 :param args: complete set of field values, in .msg order
00079 :param kwds: use keyword arguments corresponding to message field names
00080 to set specific fields.
00081 """
00082 if args or kwds:
00083 super(SensorPacket, self).__init__(*args, **kwds)
00084
00085 if self.header is None:
00086 self.header = std_msgs.msg.Header()
00087 if self.wheeldropCaster is None:
00088 self.wheeldropCaster = False
00089 if self.wheeldropLeft is None:
00090 self.wheeldropLeft = False
00091 if self.wheeldropRight is None:
00092 self.wheeldropRight = False
00093 if self.bumpLeft is None:
00094 self.bumpLeft = False
00095 if self.bumpRight is None:
00096 self.bumpRight = False
00097 if self.wall is None:
00098 self.wall = False
00099 if self.cliffLeft is None:
00100 self.cliffLeft = False
00101 if self.cliffFronLeft is None:
00102 self.cliffFronLeft = False
00103 if self.cliffFrontRight is None:
00104 self.cliffFrontRight = False
00105 if self.cliffRight is None:
00106 self.cliffRight = False
00107 if self.virtualWall is None:
00108 self.virtualWall = False
00109 if self.infraredByte is None:
00110 self.infraredByte = 0
00111 if self.advance is None:
00112 self.advance = False
00113 if self.play is None:
00114 self.play = False
00115 if self.distance is None:
00116 self.distance = 0
00117 if self.angle is None:
00118 self.angle = 0
00119 if self.chargingState is None:
00120 self.chargingState = 0
00121 if self.voltage is None:
00122 self.voltage = 0
00123 if self.current is None:
00124 self.current = 0
00125 if self.batteryTemperature is None:
00126 self.batteryTemperature = 0
00127 if self.batteryCharge is None:
00128 self.batteryCharge = 0
00129 if self.batteryCapacity is None:
00130 self.batteryCapacity = 0
00131 if self.wallSignal is None:
00132 self.wallSignal = 0
00133 if self.cliffLeftSignal is None:
00134 self.cliffLeftSignal = 0
00135 if self.cliffFrontLeftSignal is None:
00136 self.cliffFrontLeftSignal = 0
00137 if self.cliffFrontRightSignal is None:
00138 self.cliffFrontRightSignal = 0
00139 if self.cliffRightSignal is None:
00140 self.cliffRightSignal = 0
00141 if self.homeBase is None:
00142 self.homeBase = False
00143 if self.internalCharger is None:
00144 self.internalCharger = False
00145 if self.songNumber is None:
00146 self.songNumber = 0
00147 if self.songPlaying is None:
00148 self.songPlaying = 0
00149 else:
00150 self.header = std_msgs.msg.Header()
00151 self.wheeldropCaster = False
00152 self.wheeldropLeft = False
00153 self.wheeldropRight = False
00154 self.bumpLeft = False
00155 self.bumpRight = False
00156 self.wall = False
00157 self.cliffLeft = False
00158 self.cliffFronLeft = False
00159 self.cliffFrontRight = False
00160 self.cliffRight = False
00161 self.virtualWall = False
00162 self.infraredByte = 0
00163 self.advance = False
00164 self.play = False
00165 self.distance = 0
00166 self.angle = 0
00167 self.chargingState = 0
00168 self.voltage = 0
00169 self.current = 0
00170 self.batteryTemperature = 0
00171 self.batteryCharge = 0
00172 self.batteryCapacity = 0
00173 self.wallSignal = 0
00174 self.cliffLeftSignal = 0
00175 self.cliffFrontLeftSignal = 0
00176 self.cliffFrontRightSignal = 0
00177 self.cliffRightSignal = 0
00178 self.homeBase = False
00179 self.internalCharger = False
00180 self.songNumber = 0
00181 self.songPlaying = 0
00182
00183 def _get_types(self):
00184 """
00185 internal API method
00186 """
00187 return self._slot_types
00188
00189 def serialize(self, buff):
00190 """
00191 serialize message into buffer
00192 :param buff: buffer, ``StringIO``
00193 """
00194 try:
00195 _x = self
00196 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00197 _x = self.header.frame_id
00198 length = len(_x)
00199 if python3 or type(_x) == unicode:
00200 _x = _x.encode('utf-8')
00201 length = len(_x)
00202 buff.write(struct.pack('<I%ss'%length, length, _x))
00203 _x = self
00204 buff.write(_struct_14B2hBHhb7H4B.pack(_x.wheeldropCaster, _x.wheeldropLeft, _x.wheeldropRight, _x.bumpLeft, _x.bumpRight, _x.wall, _x.cliffLeft, _x.cliffFronLeft, _x.cliffFrontRight, _x.cliffRight, _x.virtualWall, _x.infraredByte, _x.advance, _x.play, _x.distance, _x.angle, _x.chargingState, _x.voltage, _x.current, _x.batteryTemperature, _x.batteryCharge, _x.batteryCapacity, _x.wallSignal, _x.cliffLeftSignal, _x.cliffFrontLeftSignal, _x.cliffFrontRightSignal, _x.cliffRightSignal, _x.homeBase, _x.internalCharger, _x.songNumber, _x.songPlaying))
00205 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00206 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00207
00208 def deserialize(self, str):
00209 """
00210 unpack serialized message in str into this message instance
00211 :param str: byte array of serialized message, ``str``
00212 """
00213 try:
00214 if self.header is None:
00215 self.header = std_msgs.msg.Header()
00216 end = 0
00217 _x = self
00218 start = end
00219 end += 12
00220 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00221 start = end
00222 end += 4
00223 (length,) = _struct_I.unpack(str[start:end])
00224 start = end
00225 end += length
00226 if python3:
00227 self.header.frame_id = str[start:end].decode('utf-8')
00228 else:
00229 self.header.frame_id = str[start:end]
00230 _x = self
00231 start = end
00232 end += 42
00233 (_x.wheeldropCaster, _x.wheeldropLeft, _x.wheeldropRight, _x.bumpLeft, _x.bumpRight, _x.wall, _x.cliffLeft, _x.cliffFronLeft, _x.cliffFrontRight, _x.cliffRight, _x.virtualWall, _x.infraredByte, _x.advance, _x.play, _x.distance, _x.angle, _x.chargingState, _x.voltage, _x.current, _x.batteryTemperature, _x.batteryCharge, _x.batteryCapacity, _x.wallSignal, _x.cliffLeftSignal, _x.cliffFrontLeftSignal, _x.cliffFrontRightSignal, _x.cliffRightSignal, _x.homeBase, _x.internalCharger, _x.songNumber, _x.songPlaying,) = _struct_14B2hBHhb7H4B.unpack(str[start:end])
00234 self.wheeldropCaster = bool(self.wheeldropCaster)
00235 self.wheeldropLeft = bool(self.wheeldropLeft)
00236 self.wheeldropRight = bool(self.wheeldropRight)
00237 self.bumpLeft = bool(self.bumpLeft)
00238 self.bumpRight = bool(self.bumpRight)
00239 self.wall = bool(self.wall)
00240 self.cliffLeft = bool(self.cliffLeft)
00241 self.cliffFronLeft = bool(self.cliffFronLeft)
00242 self.cliffFrontRight = bool(self.cliffFrontRight)
00243 self.cliffRight = bool(self.cliffRight)
00244 self.virtualWall = bool(self.virtualWall)
00245 self.advance = bool(self.advance)
00246 self.play = bool(self.play)
00247 self.homeBase = bool(self.homeBase)
00248 self.internalCharger = bool(self.internalCharger)
00249 return self
00250 except struct.error as e:
00251 raise genpy.DeserializationError(e)
00252
00253
00254 def serialize_numpy(self, buff, numpy):
00255 """
00256 serialize message with numpy array types into buffer
00257 :param buff: buffer, ``StringIO``
00258 :param numpy: numpy python module
00259 """
00260 try:
00261 _x = self
00262 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00263 _x = self.header.frame_id
00264 length = len(_x)
00265 if python3 or type(_x) == unicode:
00266 _x = _x.encode('utf-8')
00267 length = len(_x)
00268 buff.write(struct.pack('<I%ss'%length, length, _x))
00269 _x = self
00270 buff.write(_struct_14B2hBHhb7H4B.pack(_x.wheeldropCaster, _x.wheeldropLeft, _x.wheeldropRight, _x.bumpLeft, _x.bumpRight, _x.wall, _x.cliffLeft, _x.cliffFronLeft, _x.cliffFrontRight, _x.cliffRight, _x.virtualWall, _x.infraredByte, _x.advance, _x.play, _x.distance, _x.angle, _x.chargingState, _x.voltage, _x.current, _x.batteryTemperature, _x.batteryCharge, _x.batteryCapacity, _x.wallSignal, _x.cliffLeftSignal, _x.cliffFrontLeftSignal, _x.cliffFrontRightSignal, _x.cliffRightSignal, _x.homeBase, _x.internalCharger, _x.songNumber, _x.songPlaying))
00271 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00272 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00273
00274 def deserialize_numpy(self, str, numpy):
00275 """
00276 unpack serialized message in str into this message instance using numpy for array types
00277 :param str: byte array of serialized message, ``str``
00278 :param numpy: numpy python module
00279 """
00280 try:
00281 if self.header is None:
00282 self.header = std_msgs.msg.Header()
00283 end = 0
00284 _x = self
00285 start = end
00286 end += 12
00287 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 start = end
00292 end += length
00293 if python3:
00294 self.header.frame_id = str[start:end].decode('utf-8')
00295 else:
00296 self.header.frame_id = str[start:end]
00297 _x = self
00298 start = end
00299 end += 42
00300 (_x.wheeldropCaster, _x.wheeldropLeft, _x.wheeldropRight, _x.bumpLeft, _x.bumpRight, _x.wall, _x.cliffLeft, _x.cliffFronLeft, _x.cliffFrontRight, _x.cliffRight, _x.virtualWall, _x.infraredByte, _x.advance, _x.play, _x.distance, _x.angle, _x.chargingState, _x.voltage, _x.current, _x.batteryTemperature, _x.batteryCharge, _x.batteryCapacity, _x.wallSignal, _x.cliffLeftSignal, _x.cliffFrontLeftSignal, _x.cliffFrontRightSignal, _x.cliffRightSignal, _x.homeBase, _x.internalCharger, _x.songNumber, _x.songPlaying,) = _struct_14B2hBHhb7H4B.unpack(str[start:end])
00301 self.wheeldropCaster = bool(self.wheeldropCaster)
00302 self.wheeldropLeft = bool(self.wheeldropLeft)
00303 self.wheeldropRight = bool(self.wheeldropRight)
00304 self.bumpLeft = bool(self.bumpLeft)
00305 self.bumpRight = bool(self.bumpRight)
00306 self.wall = bool(self.wall)
00307 self.cliffLeft = bool(self.cliffLeft)
00308 self.cliffFronLeft = bool(self.cliffFronLeft)
00309 self.cliffFrontRight = bool(self.cliffFrontRight)
00310 self.cliffRight = bool(self.cliffRight)
00311 self.virtualWall = bool(self.virtualWall)
00312 self.advance = bool(self.advance)
00313 self.play = bool(self.play)
00314 self.homeBase = bool(self.homeBase)
00315 self.internalCharger = bool(self.internalCharger)
00316 return self
00317 except struct.error as e:
00318 raise genpy.DeserializationError(e)
00319
00320 _struct_I = genpy.struct_I
00321 _struct_3I = struct.Struct("<3I")
00322 _struct_14B2hBHhb7H4B = struct.Struct("<14B2hBHhb7H4B")