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

Source Code for Module eddiebot_node.msg._TurtlebotSensorState

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