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