Package eddiebot_node :: Package msg :: Module _RawTurtlebotSensorState
[frames] | no frames]

Source Code for Module eddiebot_node.msg._RawTurtlebotSensorState

  1  """autogenerated by genpy from turtlebot_node/RawTurtlebotSensorState.msg. Do not edit.""" 
  2  import sys 
  3  python3 = True if sys.hexversion > 0x03000000 else False 
  4  import genpy 
  5  import struct 
  6   
  7  import std_msgs.msg 
  8   
9 -class RawTurtlebotSensorState(genpy.Message):
10 _md5sum = "103d192c45e953c8bb1c3c046e89e2ff" 11 _type = "turtlebot_node/RawTurtlebotSensorState" 12 _has_header = True #flag to mark the presence of a Header object 13 _full_text = """uint8 OI_MODE_OFF = 0 14 uint8 OI_MODE_PASSIVE = 1 15 uint8 OI_MODE_SAFE = 2 16 uint8 OI_MODE_FULL = 3 17 18 uint8 REMOTE_LEFT = 129 19 uint8 REMOTE_FORWARD = 130 20 uint8 REMOTE_RIGHT = 131 21 uint8 REMOTE_SPOT = 132 22 uint8 REMOTE_MAX = 133 23 uint8 REMOTE_SMALL = 134 24 uint8 REMOTE_MEDIUM = 135 25 uint8 REMOTE_LARGE = 136 26 uint8 REMOTE_CLEAN = 136 27 uint8 REMOTE_PAUSE = 137 28 uint8 REMOTE_POWER = 138 29 uint8 REMOTE_ARC_LEFT = 139 30 uint8 REMOTE_ARC_RIGHT = 140 31 uint8 REMOTE_DRIVE_STOP = 141 32 # Scheduling remote 33 uint8 REMOTE_SEND_ALL = 142 34 uint8 REMOTE_SEEK_DOCK = 143 35 # Home base 36 uint8 REMOTE_RESERVED = 240 37 uint8 REMOTE_FORCE_FIELD = 242 38 uint8 REMOTE_GREEN_BUOY = 244 39 uint8 REMOTE_GREEN_BUOY_AND_FORCE_FIELD = 246 40 uint8 REMOTE_RED_BUOY = 248 41 uint8 REMOTE_RED_BUOY_AND_FORCE_FIELD = 250 42 uint8 REMOTE_RED_BUOY_AND_GREEN_BUOY = 252 43 uint8 REMOTE_RED_BUOY_AND_GREEN_BUOY_AND_FORCE_FIELD = 254 44 uint8 REMOTE_NONE = 255 45 46 uint8 CHARGING_NOT_CHARGING = 0 47 uint8 CHARGING_CHARGING_RECOVERY = 1 48 uint8 CHARGING_CHARGING = 2 49 uint8 CHARGING_TRICKLE_CHARGING = 3 50 uint8 CHARGING_WAITING = 4 51 uint8 CHARGING_CHARGING_ERROR = 5 52 53 Header header 54 55 uint8 bumps_wheeldrops 56 bool wall 57 bool cliff_left 58 bool cliff_front_left 59 bool cliff_front_right 60 bool cliff_right 61 bool virtual_wall 62 uint8 motor_overcurrents 63 uint8 dirt_detector_left #roomba_only 64 uint8 dirt_detector_right #roomba_only 65 uint8 remote_opcode 66 uint8 buttons 67 int16 distance # mm 68 int16 angle # degrees 69 uint8 charging_state 70 uint16 voltage # mV 71 int16 current # mA 72 int8 temperature # C 73 uint16 charge # mAh 74 uint16 capacity # mAh 75 76 uint16 wall_signal 77 uint16 cliff_left_signal 78 uint16 cliff_front_left_signal 79 uint16 cliff_front_right_signal 80 uint16 cliff_right_signal 81 uint8 user_digital_inputs 82 uint16 user_analog_input 83 uint8 charging_sources_available 84 uint8 oi_mode 85 uint8 song_number 86 bool song_playing 87 88 uint8 number_of_stream_packets 89 int16 requested_velocity # mm/s 90 int16 requested_radius # mm 91 int16 requested_right_velocity # mm/s 92 int16 requested_left_velocity # mm/s 93 94 95 ================================================================================ 96 MSG: std_msgs/Header 97 # Standard metadata for higher-level stamped data types. 98 # This is generally used to communicate timestamped data 99 # in a particular coordinate frame. 100 # 101 # sequence ID: consecutively increasing ID 102 uint32 seq 103 #Two-integer timestamp that is expressed as: 104 # * stamp.secs: seconds (stamp_secs) since epoch 105 # * stamp.nsecs: nanoseconds since stamp_secs 106 # time-handling sugar is provided by the client library 107 time stamp 108 #Frame this data is associated with 109 # 0: no frame 110 # 1: global frame 111 string frame_id 112 113 """ 114 # Pseudo-constants 115 OI_MODE_OFF = 0 116 OI_MODE_PASSIVE = 1 117 OI_MODE_SAFE = 2 118 OI_MODE_FULL = 3 119 REMOTE_LEFT = 129 120 REMOTE_FORWARD = 130 121 REMOTE_RIGHT = 131 122 REMOTE_SPOT = 132 123 REMOTE_MAX = 133 124 REMOTE_SMALL = 134 125 REMOTE_MEDIUM = 135 126 REMOTE_LARGE = 136 127 REMOTE_CLEAN = 136 128 REMOTE_PAUSE = 137 129 REMOTE_POWER = 138 130 REMOTE_ARC_LEFT = 139 131 REMOTE_ARC_RIGHT = 140 132 REMOTE_DRIVE_STOP = 141 133 REMOTE_SEND_ALL = 142 134 REMOTE_SEEK_DOCK = 143 135 REMOTE_RESERVED = 240 136 REMOTE_FORCE_FIELD = 242 137 REMOTE_GREEN_BUOY = 244 138 REMOTE_GREEN_BUOY_AND_FORCE_FIELD = 246 139 REMOTE_RED_BUOY = 248 140 REMOTE_RED_BUOY_AND_FORCE_FIELD = 250 141 REMOTE_RED_BUOY_AND_GREEN_BUOY = 252 142 REMOTE_RED_BUOY_AND_GREEN_BUOY_AND_FORCE_FIELD = 254 143 REMOTE_NONE = 255 144 CHARGING_NOT_CHARGING = 0 145 CHARGING_CHARGING_RECOVERY = 1 146 CHARGING_CHARGING = 2 147 CHARGING_TRICKLE_CHARGING = 3 148 CHARGING_WAITING = 4 149 CHARGING_CHARGING_ERROR = 5 150 151 __slots__ = ['header','bumps_wheeldrops','wall','cliff_left','cliff_front_left','cliff_front_right','cliff_right','virtual_wall','motor_overcurrents','dirt_detector_left','dirt_detector_right','remote_opcode','buttons','distance','angle','charging_state','voltage','current','temperature','charge','capacity','wall_signal','cliff_left_signal','cliff_front_left_signal','cliff_front_right_signal','cliff_right_signal','user_digital_inputs','user_analog_input','charging_sources_available','oi_mode','song_number','song_playing','number_of_stream_packets','requested_velocity','requested_radius','requested_right_velocity','requested_left_velocity'] 152 _slot_types = ['std_msgs/Header','uint8','bool','bool','bool','bool','bool','bool','uint8','uint8','uint8','uint8','uint8','int16','int16','uint8','uint16','int16','int8','uint16','uint16','uint16','uint16','uint16','uint16','uint16','uint8','uint16','uint8','uint8','uint8','bool','uint8','int16','int16','int16','int16'] 153
154 - def __init__(self, *args, **kwds):
155 """ 156 Constructor. Any message fields that are implicitly/explicitly 157 set to None will be assigned a default value. The recommend 158 use is keyword arguments as this is more robust to future message 159 changes. You cannot mix in-order arguments and keyword arguments. 160 161 The available fields are: 162 header,bumps_wheeldrops,wall,cliff_left,cliff_front_left,cliff_front_right,cliff_right,virtual_wall,motor_overcurrents,dirt_detector_left,dirt_detector_right,remote_opcode,buttons,distance,angle,charging_state,voltage,current,temperature,charge,capacity,wall_signal,cliff_left_signal,cliff_front_left_signal,cliff_front_right_signal,cliff_right_signal,user_digital_inputs,user_analog_input,charging_sources_available,oi_mode,song_number,song_playing,number_of_stream_packets,requested_velocity,requested_radius,requested_right_velocity,requested_left_velocity 163 164 :param args: complete set of field values, in .msg order 165 :param kwds: use keyword arguments corresponding to message field names 166 to set specific fields. 167 """ 168 if args or kwds: 169 super(RawTurtlebotSensorState, self).__init__(*args, **kwds) 170 #message fields cannot be None, assign default values for those that are 171 if self.header is None: 172 self.header = std_msgs.msg.Header() 173 if self.bumps_wheeldrops is None: 174 self.bumps_wheeldrops = 0 175 if self.wall is None: 176 self.wall = False 177 if self.cliff_left is None: 178 self.cliff_left = False 179 if self.cliff_front_left is None: 180 self.cliff_front_left = False 181 if self.cliff_front_right is None: 182 self.cliff_front_right = False 183 if self.cliff_right is None: 184 self.cliff_right = False 185 if self.virtual_wall is None: 186 self.virtual_wall = False 187 if self.motor_overcurrents is None: 188 self.motor_overcurrents = 0 189 if self.dirt_detector_left is None: 190 self.dirt_detector_left = 0 191 if self.dirt_detector_right is None: 192 self.dirt_detector_right = 0 193 if self.remote_opcode is None: 194 self.remote_opcode = 0 195 if self.buttons is None: 196 self.buttons = 0 197 if self.distance is None: 198 self.distance = 0 199 if self.angle is None: 200 self.angle = 0 201 if self.charging_state is None: 202 self.charging_state = 0 203 if self.voltage is None: 204 self.voltage = 0 205 if self.current is None: 206 self.current = 0 207 if self.temperature is None: 208 self.temperature = 0 209 if self.charge is None: 210 self.charge = 0 211 if self.capacity is None: 212 self.capacity = 0 213 if self.wall_signal is None: 214 self.wall_signal = 0 215 if self.cliff_left_signal is None: 216 self.cliff_left_signal = 0 217 if self.cliff_front_left_signal is None: 218 self.cliff_front_left_signal = 0 219 if self.cliff_front_right_signal is None: 220 self.cliff_front_right_signal = 0 221 if self.cliff_right_signal is None: 222 self.cliff_right_signal = 0 223 if self.user_digital_inputs is None: 224 self.user_digital_inputs = 0 225 if self.user_analog_input is None: 226 self.user_analog_input = 0 227 if self.charging_sources_available is None: 228 self.charging_sources_available = 0 229 if self.oi_mode is None: 230 self.oi_mode = 0 231 if self.song_number is None: 232 self.song_number = 0 233 if self.song_playing is None: 234 self.song_playing = False 235 if self.number_of_stream_packets is None: 236 self.number_of_stream_packets = 0 237 if self.requested_velocity is None: 238 self.requested_velocity = 0 239 if self.requested_radius is None: 240 self.requested_radius = 0 241 if self.requested_right_velocity is None: 242 self.requested_right_velocity = 0 243 if self.requested_left_velocity is None: 244 self.requested_left_velocity = 0 245 else: 246 self.header = std_msgs.msg.Header() 247 self.bumps_wheeldrops = 0 248 self.wall = False 249 self.cliff_left = False 250 self.cliff_front_left = False 251 self.cliff_front_right = False 252 self.cliff_right = False 253 self.virtual_wall = False 254 self.motor_overcurrents = 0 255 self.dirt_detector_left = 0 256 self.dirt_detector_right = 0 257 self.remote_opcode = 0 258 self.buttons = 0 259 self.distance = 0 260 self.angle = 0 261 self.charging_state = 0 262 self.voltage = 0 263 self.current = 0 264 self.temperature = 0 265 self.charge = 0 266 self.capacity = 0 267 self.wall_signal = 0 268 self.cliff_left_signal = 0 269 self.cliff_front_left_signal = 0 270 self.cliff_front_right_signal = 0 271 self.cliff_right_signal = 0 272 self.user_digital_inputs = 0 273 self.user_analog_input = 0 274 self.charging_sources_available = 0 275 self.oi_mode = 0 276 self.song_number = 0 277 self.song_playing = False 278 self.number_of_stream_packets = 0 279 self.requested_velocity = 0 280 self.requested_radius = 0 281 self.requested_right_velocity = 0 282 self.requested_left_velocity = 0
283
284 - def _get_types(self):
285 """ 286 internal API method 287 """ 288 return self._slot_types
289
290 - def serialize(self, buff):
291 """ 292 serialize message into buffer 293 :param buff: buffer, ``StringIO`` 294 """ 295 try: 296 _x = self 297 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 298 _x = self.header.frame_id 299 length = len(_x) 300 if python3 or type(_x) == unicode: 301 _x = _x.encode('utf-8') 302 length = len(_x) 303 buff.write(struct.pack('<I%ss'%length, length, _x)) 304 _x = self 305 buff.write(_struct_12B2hBHhb7HBH5B4h.pack(_x.bumps_wheeldrops, _x.wall, _x.cliff_left, _x.cliff_front_left, _x.cliff_front_right, _x.cliff_right, _x.virtual_wall, _x.motor_overcurrents, _x.dirt_detector_left, _x.dirt_detector_right, _x.remote_opcode, _x.buttons, _x.distance, _x.angle, _x.charging_state, _x.voltage, _x.current, _x.temperature, _x.charge, _x.capacity, _x.wall_signal, _x.cliff_left_signal, _x.cliff_front_left_signal, _x.cliff_front_right_signal, _x.cliff_right_signal, _x.user_digital_inputs, _x.user_analog_input, _x.charging_sources_available, _x.oi_mode, _x.song_number, _x.song_playing, _x.number_of_stream_packets, _x.requested_velocity, _x.requested_radius, _x.requested_right_velocity, _x.requested_left_velocity)) 306 except struct.error as se: self._check_types(se) 307 except TypeError as te: self._check_types(te)
308
309 - def deserialize(self, str):
310 """ 311 unpack serialized message in str into this message instance 312 :param str: byte array of serialized message, ``str`` 313 """ 314 try: 315 if self.header is None: 316 self.header = std_msgs.msg.Header() 317 end = 0 318 _x = self 319 start = end 320 end += 12 321 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 322 start = end 323 end += 4 324 (length,) = _struct_I.unpack(str[start:end]) 325 start = end 326 end += length 327 if python3: 328 self.header.frame_id = str[start:end].decode('utf-8') 329 else: 330 self.header.frame_id = str[start:end] 331 _x = self 332 start = end 333 end += 52 334 (_x.bumps_wheeldrops, _x.wall, _x.cliff_left, _x.cliff_front_left, _x.cliff_front_right, _x.cliff_right, _x.virtual_wall, _x.motor_overcurrents, _x.dirt_detector_left, _x.dirt_detector_right, _x.remote_opcode, _x.buttons, _x.distance, _x.angle, _x.charging_state, _x.voltage, _x.current, _x.temperature, _x.charge, _x.capacity, _x.wall_signal, _x.cliff_left_signal, _x.cliff_front_left_signal, _x.cliff_front_right_signal, _x.cliff_right_signal, _x.user_digital_inputs, _x.user_analog_input, _x.charging_sources_available, _x.oi_mode, _x.song_number, _x.song_playing, _x.number_of_stream_packets, _x.requested_velocity, _x.requested_radius, _x.requested_right_velocity, _x.requested_left_velocity,) = _struct_12B2hBHhb7HBH5B4h.unpack(str[start:end]) 335 self.wall = bool(self.wall) 336 self.cliff_left = bool(self.cliff_left) 337 self.cliff_front_left = bool(self.cliff_front_left) 338 self.cliff_front_right = bool(self.cliff_front_right) 339 self.cliff_right = bool(self.cliff_right) 340 self.virtual_wall = bool(self.virtual_wall) 341 self.song_playing = bool(self.song_playing) 342 return self 343 except struct.error as e: 344 raise genpy.DeserializationError(e) #most likely buffer underfill
345 346
347 - def serialize_numpy(self, buff, numpy):
348 """ 349 serialize message with numpy array types into buffer 350 :param buff: buffer, ``StringIO`` 351 :param numpy: numpy python module 352 """ 353 try: 354 _x = self 355 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 356 _x = self.header.frame_id 357 length = len(_x) 358 if python3 or type(_x) == unicode: 359 _x = _x.encode('utf-8') 360 length = len(_x) 361 buff.write(struct.pack('<I%ss'%length, length, _x)) 362 _x = self 363 buff.write(_struct_12B2hBHhb7HBH5B4h.pack(_x.bumps_wheeldrops, _x.wall, _x.cliff_left, _x.cliff_front_left, _x.cliff_front_right, _x.cliff_right, _x.virtual_wall, _x.motor_overcurrents, _x.dirt_detector_left, _x.dirt_detector_right, _x.remote_opcode, _x.buttons, _x.distance, _x.angle, _x.charging_state, _x.voltage, _x.current, _x.temperature, _x.charge, _x.capacity, _x.wall_signal, _x.cliff_left_signal, _x.cliff_front_left_signal, _x.cliff_front_right_signal, _x.cliff_right_signal, _x.user_digital_inputs, _x.user_analog_input, _x.charging_sources_available, _x.oi_mode, _x.song_number, _x.song_playing, _x.number_of_stream_packets, _x.requested_velocity, _x.requested_radius, _x.requested_right_velocity, _x.requested_left_velocity)) 364 except struct.error as se: self._check_types(se) 365 except TypeError as te: self._check_types(te)
366
367 - def deserialize_numpy(self, str, numpy):
368 """ 369 unpack serialized message in str into this message instance using numpy for array types 370 :param str: byte array of serialized message, ``str`` 371 :param numpy: numpy python module 372 """ 373 try: 374 if self.header is None: 375 self.header = std_msgs.msg.Header() 376 end = 0 377 _x = self 378 start = end 379 end += 12 380 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 381 start = end 382 end += 4 383 (length,) = _struct_I.unpack(str[start:end]) 384 start = end 385 end += length 386 if python3: 387 self.header.frame_id = str[start:end].decode('utf-8') 388 else: 389 self.header.frame_id = str[start:end] 390 _x = self 391 start = end 392 end += 52 393 (_x.bumps_wheeldrops, _x.wall, _x.cliff_left, _x.cliff_front_left, _x.cliff_front_right, _x.cliff_right, _x.virtual_wall, _x.motor_overcurrents, _x.dirt_detector_left, _x.dirt_detector_right, _x.remote_opcode, _x.buttons, _x.distance, _x.angle, _x.charging_state, _x.voltage, _x.current, _x.temperature, _x.charge, _x.capacity, _x.wall_signal, _x.cliff_left_signal, _x.cliff_front_left_signal, _x.cliff_front_right_signal, _x.cliff_right_signal, _x.user_digital_inputs, _x.user_analog_input, _x.charging_sources_available, _x.oi_mode, _x.song_number, _x.song_playing, _x.number_of_stream_packets, _x.requested_velocity, _x.requested_radius, _x.requested_right_velocity, _x.requested_left_velocity,) = _struct_12B2hBHhb7HBH5B4h.unpack(str[start:end]) 394 self.wall = bool(self.wall) 395 self.cliff_left = bool(self.cliff_left) 396 self.cliff_front_left = bool(self.cliff_front_left) 397 self.cliff_front_right = bool(self.cliff_front_right) 398 self.cliff_right = bool(self.cliff_right) 399 self.virtual_wall = bool(self.virtual_wall) 400 self.song_playing = bool(self.song_playing) 401 return self 402 except struct.error as e: 403 raise genpy.DeserializationError(e) #most likely buffer underfill
404 405 _struct_I = genpy.struct_I 406 _struct_3I = struct.Struct("<3I") 407 _struct_12B2hBHhb7HBH5B4h = struct.Struct("<12B2hBHhb7HBH5B4h") 408