00001
00002 '''
00003 mavlink python utility functions
00004
00005 Copyright Andrew Tridgell 2011
00006 Released under GNU GPL version 3 or later
00007 '''
00008
00009 import socket, math, struct, time, os, fnmatch, array, sys, errno
00010 import select
00011
00012
00013
00014
00015 try:
00016 import json
00017 from pymavlink.dialects.v10 import ardupilotmega
00018 except Exception:
00019 pass
00020
00021
00022 from math import *
00023 from .mavextra import *
00024
00025 '''
00026 Support having a $HOME/.pymavlink/mavextra.py for extra graphing functions
00027 '''
00028 home = os.getenv('HOME')
00029 if home is not None:
00030 extra = os.path.join(home, '.pymavlink', 'mavextra.py')
00031 if os.path.exists(extra):
00032 import imp
00033 mavuser = imp.load_source('pymavlink.mavuser', extra)
00034 from pymavlink.mavuser import *
00035
00036
00037
00038 mavlink = None
00039
00040
00041
00042 mavfile_global = None
00043
00044
00045 default_native = False
00046
00047
00048 if not 'MAVLINK_DIALECT' in os.environ:
00049 os.environ['MAVLINK_DIALECT'] = 'ardupilotmega'
00050
00051 def mavlink10():
00052 '''return True if using MAVLink 1.0'''
00053 return not 'MAVLINK09' in os.environ
00054
00055 def evaluate_expression(expression, vars):
00056 '''evaluation an expression'''
00057 try:
00058 v = eval(expression, globals(), vars)
00059 except NameError:
00060 return None
00061 except ZeroDivisionError:
00062 return None
00063 return v
00064
00065 def evaluate_condition(condition, vars):
00066 '''evaluation a conditional (boolean) statement'''
00067 if condition is None:
00068 return True
00069 v = evaluate_expression(condition, vars)
00070 if v is None:
00071 return False
00072 return v
00073
00074 class location(object):
00075 '''represent a GPS coordinate'''
00076 def __init__(self, lat, lng, alt=0, heading=0):
00077 self.lat = lat
00078 self.lng = lng
00079 self.alt = alt
00080 self.heading = heading
00081
00082 def __str__(self):
00083 return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)
00084
00085 def set_dialect(dialect):
00086 '''set the MAVLink dialect to work with.
00087 For example, set_dialect("ardupilotmega")
00088 '''
00089 global mavlink, current_dialect
00090 from .generator import mavparse
00091 if mavlink is None or mavlink.WIRE_PROTOCOL_VERSION == "1.0" or not 'MAVLINK09' in os.environ:
00092 wire_protocol = mavparse.PROTOCOL_1_0
00093 modname = "pymavlink.dialects.v10." + dialect
00094 else:
00095 wire_protocol = mavparse.PROTOCOL_0_9
00096 modname = "pymavlink.dialects.v09." + dialect
00097
00098 try:
00099 mod = __import__(modname)
00100 except Exception:
00101
00102 from .generator.mavgen import mavgen_python_dialect
00103 mavgen_python_dialect(dialect, wire_protocol)
00104 mod = __import__(modname)
00105 components = modname.split('.')
00106 for comp in components[1:]:
00107 mod = getattr(mod, comp)
00108 current_dialect = dialect
00109 mavlink = mod
00110
00111
00112 set_dialect(os.environ['MAVLINK_DIALECT'])
00113
00114 class mavfile(object):
00115 '''a generic mavlink port'''
00116 def __init__(self, fd, address, source_system=255, notimestamps=False, input=True, use_native=default_native):
00117 global mavfile_global
00118 if input:
00119 mavfile_global = self
00120 self.fd = fd
00121 self.address = address
00122 self.messages = { 'MAV' : self }
00123 if mavlink.WIRE_PROTOCOL_VERSION == "1.0":
00124 self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0)
00125 mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message
00126 else:
00127 self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0)
00128 self.params = {}
00129 self.target_system = 0
00130 self.target_component = 0
00131 self.source_system = source_system
00132 self.first_byte = True
00133 self.robust_parsing = True
00134 self.mav = mavlink.MAVLink(self, srcSystem=self.source_system, use_native=use_native)
00135 self.mav.robust_parsing = self.robust_parsing
00136 self.logfile = None
00137 self.logfile_raw = None
00138 self.param_fetch_in_progress = False
00139 self.param_fetch_complete = False
00140 self.start_time = time.time()
00141 self.flightmode = "UNKNOWN"
00142 self.vehicle_type = "UNKNOWN"
00143 self.mav_type = mavlink.MAV_TYPE_FIXED_WING
00144 self.base_mode = 0
00145 self.timestamp = 0
00146 self.message_hooks = []
00147 self.idle_hooks = []
00148 self.uptime = 0.0
00149 self.notimestamps = notimestamps
00150 self._timestamp = None
00151 self.ground_pressure = None
00152 self.ground_temperature = None
00153 self.altitude = 0
00154 self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
00155 self.last_seq = {}
00156 self.mav_loss = 0
00157 self.mav_count = 0
00158 self.stop_on_EOF = False
00159 self.portdead = False
00160
00161 def auto_mavlink_version(self, buf):
00162 '''auto-switch mavlink protocol version'''
00163 global mavlink
00164 if len(buf) == 0:
00165 return
00166 try:
00167 magic = ord(buf[0])
00168 except:
00169 magic = buf[0]
00170 if not magic in [ 85, 254 ]:
00171 return
00172 self.first_byte = False
00173 if self.WIRE_PROTOCOL_VERSION == "0.9" and magic == 254:
00174 self.WIRE_PROTOCOL_VERSION = "1.0"
00175 set_dialect(current_dialect)
00176 elif self.WIRE_PROTOCOL_VERSION == "1.0" and magic == 85:
00177 self.WIRE_PROTOCOL_VERSION = "0.9"
00178 set_dialect(current_dialect)
00179 os.environ['MAVLINK09'] = '1'
00180 else:
00181 return
00182
00183 (callback, callback_args, callback_kwargs) = (self.mav.callback,
00184 self.mav.callback_args,
00185 self.mav.callback_kwargs)
00186 self.mav = mavlink.MAVLink(self, srcSystem=self.source_system)
00187 self.mav.robust_parsing = self.robust_parsing
00188 self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
00189 (self.mav.callback, self.mav.callback_args, self.mav.callback_kwargs) = (callback,
00190 callback_args,
00191 callback_kwargs)
00192
00193 def recv(self, n=None):
00194 '''default recv method'''
00195 raise RuntimeError('no recv() method supplied')
00196
00197 def close(self, n=None):
00198 '''default close method'''
00199 raise RuntimeError('no close() method supplied')
00200
00201 def write(self, buf):
00202 '''default write method'''
00203 raise RuntimeError('no write() method supplied')
00204
00205
00206 def select(self, timeout):
00207 '''wait for up to timeout seconds for more data'''
00208 if self.fd is None:
00209 time.sleep(min(timeout,0.5))
00210 return True
00211 try:
00212 (rin, win, xin) = select.select([self.fd], [], [], timeout)
00213 except select.error:
00214 return False
00215 return len(rin) == 1
00216
00217 def pre_message(self):
00218 '''default pre message call'''
00219 return
00220
00221 def set_rtscts(self, enable):
00222 '''enable/disable RTS/CTS if applicable'''
00223 return
00224
00225 def post_message(self, msg):
00226 '''default post message call'''
00227 if '_posted' in msg.__dict__:
00228 return
00229 msg._posted = True
00230 msg._timestamp = time.time()
00231 type = msg.get_type()
00232 if type != 'HEARTBEAT' or (msg.type != mavlink.MAV_TYPE_GCS and msg.type != mavlink.MAV_TYPE_GIMBAL):
00233 self.messages[type] = msg
00234
00235 if 'usec' in msg.__dict__:
00236 self.uptime = msg.usec * 1.0e-6
00237 if 'time_boot_ms' in msg.__dict__:
00238 self.uptime = msg.time_boot_ms * 1.0e-3
00239
00240 if self._timestamp is not None:
00241 if self.notimestamps:
00242 msg._timestamp = self.uptime
00243 else:
00244 msg._timestamp = self._timestamp
00245
00246 src_system = msg.get_srcSystem()
00247 src_component = msg.get_srcComponent()
00248 src_tuple = (src_system, src_component)
00249 radio_tuple = (ord('3'), ord('D'))
00250 if not (src_tuple == radio_tuple or msg.get_type() == 'BAD_DATA'):
00251 if not src_tuple in self.last_seq:
00252 last_seq = -1
00253 else:
00254 last_seq = self.last_seq[src_tuple]
00255 seq = (last_seq+1) % 256
00256 seq2 = msg.get_seq()
00257 if seq != seq2 and last_seq != -1:
00258 diff = (seq2 - seq) % 256
00259 self.mav_loss += diff
00260
00261 self.last_seq[src_tuple] = seq2
00262 self.mav_count += 1
00263
00264 self.timestamp = msg._timestamp
00265 if type == 'HEARTBEAT' and msg.get_srcComponent() != mavlink.MAV_COMP_ID_GIMBAL:
00266 self.target_system = msg.get_srcSystem()
00267 self.target_component = msg.get_srcComponent()
00268 if mavlink.WIRE_PROTOCOL_VERSION == '1.0' and msg.type != mavlink.MAV_TYPE_GCS:
00269 self.flightmode = mode_string_v10(msg)
00270 self.mav_type = msg.type
00271 self.base_mode = msg.base_mode
00272 elif type == 'PARAM_VALUE':
00273 s = str(msg.param_id)
00274 self.params[str(msg.param_id)] = msg.param_value
00275 if msg.param_index+1 == msg.param_count:
00276 self.param_fetch_in_progress = False
00277 self.param_fetch_complete = True
00278 elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9':
00279 self.flightmode = mode_string_v09(msg)
00280 elif type == 'GPS_RAW':
00281 if self.messages['HOME'].fix_type < 2:
00282 self.messages['HOME'] = msg
00283 elif type == 'GPS_RAW_INT':
00284 if self.messages['HOME'].fix_type < 3:
00285 self.messages['HOME'] = msg
00286 for hook in self.message_hooks:
00287 hook(self, msg)
00288
00289
00290 def packet_loss(self):
00291 '''packet loss as a percentage'''
00292 if self.mav_count == 0:
00293 return 0
00294 return (100.0*self.mav_loss)/(self.mav_count+self.mav_loss)
00295
00296
00297 def recv_msg(self):
00298 '''message receive routine'''
00299 self.pre_message()
00300 while True:
00301 n = self.mav.bytes_needed()
00302 s = self.recv(n)
00303 numnew = len(s)
00304
00305 if numnew != 0:
00306 if self.logfile_raw:
00307 self.logfile_raw.write(str(s))
00308 if self.first_byte:
00309 self.auto_mavlink_version(s)
00310
00311
00312
00313 msg = self.mav.parse_char(s)
00314 if msg:
00315 if self.logfile and msg.get_type() != 'BAD_DATA' :
00316 usec = int(time.time() * 1.0e6) & ~3
00317 self.logfile.write(str(struct.pack('>Q', usec) + msg.get_msgbuf()))
00318 self.post_message(msg)
00319 return msg
00320 else:
00321
00322
00323 if numnew == 0:
00324 return None
00325
00326 def recv_match(self, condition=None, type=None, blocking=False, timeout=None):
00327 '''recv the next MAVLink message that matches the given condition
00328 type can be a string or a list of strings'''
00329 if type is not None and not isinstance(type, list):
00330 type = [type]
00331 start_time = time.time()
00332 while True:
00333 if timeout is not None:
00334 now = time.time()
00335 if now < start_time:
00336 start_time = now
00337 if start_time + timeout < time.time():
00338 return None
00339 m = self.recv_msg()
00340 if m is None:
00341 if blocking:
00342 for hook in self.idle_hooks:
00343 hook(self)
00344 if timeout is None:
00345 self.select(0.05)
00346 else:
00347 self.select(timeout/2)
00348 continue
00349 return None
00350 if type is not None and not m.get_type() in type:
00351 continue
00352 if not evaluate_condition(condition, self.messages):
00353 continue
00354 return m
00355
00356 def check_condition(self, condition):
00357 '''check if a condition is true'''
00358 return evaluate_condition(condition, self.messages)
00359
00360 def mavlink10(self):
00361 '''return True if using MAVLink 1.0'''
00362 return self.WIRE_PROTOCOL_VERSION == "1.0"
00363
00364 def setup_logfile(self, logfile, mode='w'):
00365 '''start logging to the given logfile, with timestamps'''
00366 self.logfile = open(logfile, mode=mode)
00367
00368 def setup_logfile_raw(self, logfile, mode='w'):
00369 '''start logging raw bytes to the given logfile, without timestamps'''
00370 self.logfile_raw = open(logfile, mode=mode)
00371
00372 def wait_heartbeat(self, blocking=True):
00373 '''wait for a heartbeat so we know the target system IDs'''
00374 return self.recv_match(type='HEARTBEAT', blocking=blocking)
00375
00376 def param_fetch_all(self):
00377 '''initiate fetch of all parameters'''
00378 if time.time() - getattr(self, 'param_fetch_start', 0) < 2.0:
00379
00380 return
00381 self.param_fetch_start = time.time()
00382 self.param_fetch_in_progress = True
00383 self.mav.param_request_list_send(self.target_system, self.target_component)
00384
00385 def param_fetch_one(self, name):
00386 '''initiate fetch of one parameter'''
00387 try:
00388 idx = int(name)
00389 self.mav.param_request_read_send(self.target_system, self.target_component, "", idx)
00390 except Exception:
00391 self.mav.param_request_read_send(self.target_system, self.target_component, name, -1)
00392
00393 def time_since(self, mtype):
00394 '''return the time since the last message of type mtype was received'''
00395 if not mtype in self.messages:
00396 return time.time() - self.start_time
00397 return time.time() - self.messages[mtype]._timestamp
00398
00399 def param_set_send(self, parm_name, parm_value, parm_type=None):
00400 '''wrapper for parameter set'''
00401 if self.mavlink10():
00402 if parm_type == None:
00403 parm_type = mavlink.MAVLINK_TYPE_FLOAT
00404 self.mav.param_set_send(self.target_system, self.target_component,
00405 parm_name, parm_value, parm_type)
00406 else:
00407 self.mav.param_set_send(self.target_system, self.target_component,
00408 parm_name, parm_value)
00409
00410 def waypoint_request_list_send(self):
00411 '''wrapper for waypoint_request_list_send'''
00412 if self.mavlink10():
00413 self.mav.mission_request_list_send(self.target_system, self.target_component)
00414 else:
00415 self.mav.waypoint_request_list_send(self.target_system, self.target_component)
00416
00417 def waypoint_clear_all_send(self):
00418 '''wrapper for waypoint_clear_all_send'''
00419 if self.mavlink10():
00420 self.mav.mission_clear_all_send(self.target_system, self.target_component)
00421 else:
00422 self.mav.waypoint_clear_all_send(self.target_system, self.target_component)
00423
00424 def waypoint_request_send(self, seq):
00425 '''wrapper for waypoint_request_send'''
00426 if self.mavlink10():
00427 self.mav.mission_request_send(self.target_system, self.target_component, seq)
00428 else:
00429 self.mav.waypoint_request_send(self.target_system, self.target_component, seq)
00430
00431 def waypoint_set_current_send(self, seq):
00432 '''wrapper for waypoint_set_current_send'''
00433 if self.mavlink10():
00434 self.mav.mission_set_current_send(self.target_system, self.target_component, seq)
00435 else:
00436 self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq)
00437
00438 def waypoint_current(self):
00439 '''return current waypoint'''
00440 if self.mavlink10():
00441 m = self.recv_match(type='MISSION_CURRENT', blocking=True)
00442 else:
00443 m = self.recv_match(type='WAYPOINT_CURRENT', blocking=True)
00444 return m.seq
00445
00446 def waypoint_count_send(self, seq):
00447 '''wrapper for waypoint_count_send'''
00448 if self.mavlink10():
00449 self.mav.mission_count_send(self.target_system, self.target_component, seq)
00450 else:
00451 self.mav.waypoint_count_send(self.target_system, self.target_component, seq)
00452
00453 def set_mode_flag(self, flag, enable):
00454 '''
00455 Enables/ disables MAV_MODE_FLAG
00456 @param flag The mode flag,
00457 see MAV_MODE_FLAG enum
00458 @param enable Enable the flag, (True/False)
00459 '''
00460 if self.mavlink10():
00461 mode = self.base_mode
00462 if (enable == True):
00463 mode = mode | flag
00464 elif (enable == False):
00465 mode = mode & ~flag
00466 self.mav.command_long_send(self.target_system, self.target_component,
00467 mavlink.MAV_CMD_DO_SET_MODE, 0,
00468 mode,
00469 0, 0, 0, 0, 0, 0)
00470 else:
00471 print("Set mode flag not supported")
00472
00473 def set_mode_auto(self):
00474 '''enter auto mode'''
00475 if self.mavlink10():
00476 self.mav.command_long_send(self.target_system, self.target_component,
00477 mavlink.MAV_CMD_MISSION_START, 0, 0, 0, 0, 0, 0, 0, 0)
00478 else:
00479 MAV_ACTION_SET_AUTO = 13
00480 self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_AUTO)
00481
00482 def mode_mapping(self):
00483 '''return dictionary mapping mode names to numbers, or None if unknown'''
00484 mav_type = self.field('HEARTBEAT', 'type', self.mav_type)
00485 if mav_type is None:
00486 return None
00487 map = None
00488 if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
00489 mavlink.MAV_TYPE_HELICOPTER,
00490 mavlink.MAV_TYPE_HEXAROTOR,
00491 mavlink.MAV_TYPE_OCTOROTOR,
00492 mavlink.MAV_TYPE_TRICOPTER]:
00493 map = mode_mapping_acm
00494 if mav_type == mavlink.MAV_TYPE_FIXED_WING:
00495 map = mode_mapping_apm
00496 if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
00497 map = mode_mapping_rover
00498 if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
00499 map = mode_mapping_tracker
00500 if map is None:
00501 return None
00502 inv_map = dict((a, b) for (b, a) in list(map.items()))
00503 return inv_map
00504
00505 def set_mode(self, mode):
00506 '''enter arbitrary mode'''
00507 if isinstance(mode, str):
00508 map = self.mode_mapping()
00509 if map is None or mode not in map:
00510 print("Unknown mode '%s'" % mode)
00511 return
00512 mode = map[mode]
00513 self.mav.set_mode_send(self.target_system,
00514 mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
00515 mode)
00516
00517 def set_mode_rtl(self):
00518 '''enter RTL mode'''
00519 if self.mavlink10():
00520 self.mav.command_long_send(self.target_system, self.target_component,
00521 mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0, 0, 0, 0, 0, 0)
00522 else:
00523 MAV_ACTION_RETURN = 3
00524 self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_RETURN)
00525
00526 def set_mode_manual(self):
00527 '''enter MANUAL mode'''
00528 if self.mavlink10():
00529 self.mav.command_long_send(self.target_system, self.target_component,
00530 mavlink.MAV_CMD_DO_SET_MODE, 0,
00531 mavlink.MAV_MODE_MANUAL_ARMED,
00532 0, 0, 0, 0, 0, 0)
00533 else:
00534 MAV_ACTION_SET_MANUAL = 12
00535 self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_MANUAL)
00536
00537 def set_mode_fbwa(self):
00538 '''enter FBWA mode'''
00539 if self.mavlink10():
00540 self.mav.command_long_send(self.target_system, self.target_component,
00541 mavlink.MAV_CMD_DO_SET_MODE, 0,
00542 mavlink.MAV_MODE_STABILIZE_ARMED,
00543 0, 0, 0, 0, 0, 0)
00544 else:
00545 print("Forcing FBWA not supported")
00546
00547 def set_mode_loiter(self):
00548 '''enter LOITER mode'''
00549 if self.mavlink10():
00550 self.mav.command_long_send(self.target_system, self.target_component,
00551 mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 0, 0, 0, 0, 0, 0)
00552 else:
00553 MAV_ACTION_LOITER = 27
00554 self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_LOITER)
00555
00556 def set_servo(self, channel, pwm):
00557 '''set a servo value'''
00558 self.mav.command_long_send(self.target_system, self.target_component,
00559 mavlink.MAV_CMD_DO_SET_SERVO, 0,
00560 channel, pwm,
00561 0, 0, 0, 0, 0)
00562
00563
00564 def set_relay(self, relay_pin=0, state=True):
00565 '''Set relay_pin to value of state'''
00566 if self.mavlink10():
00567 self.mav.command_long_send(
00568 self.target_system,
00569 self.target_component,
00570 mavlink.MAV_CMD_DO_SET_RELAY,
00571 0,
00572 relay_pin,
00573 int(state),
00574 0,
00575 0,
00576 0,
00577 0,
00578 0)
00579 else:
00580 print("Setting relays not supported.")
00581
00582 def calibrate_level(self):
00583 '''calibrate accels (1D version)'''
00584 self.mav.command_long_send(self.target_system, self.target_component,
00585 mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
00586 1, 1, 0, 0, 0, 0, 0)
00587
00588 def calibrate_pressure(self):
00589 '''calibrate pressure'''
00590 if self.mavlink10():
00591 self.mav.command_long_send(self.target_system, self.target_component,
00592 mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
00593 0, 0, 1, 0, 0, 0, 0)
00594 else:
00595 MAV_ACTION_CALIBRATE_PRESSURE = 20
00596 self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_CALIBRATE_PRESSURE)
00597
00598 def reboot_autopilot(self, hold_in_bootloader=False):
00599 '''reboot the autopilot'''
00600 if self.mavlink10():
00601 if hold_in_bootloader:
00602 param1 = 3
00603 else:
00604 param1 = 1
00605 self.mav.command_long_send(self.target_system, self.target_component,
00606 mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
00607 param1, 0, 0, 0, 0, 0, 0)
00608
00609
00610 self.mav.command_long_send(self.target_system, self.target_component,
00611 mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
00612 1, 0, 0, 0, 0, 0, 0)
00613
00614 def wait_gps_fix(self):
00615 self.recv_match(type='VFR_HUD', blocking=True)
00616 if self.mavlink10():
00617 self.recv_match(type='GPS_RAW_INT', blocking=True,
00618 condition='GPS_RAW_INT.fix_type==3 and GPS_RAW_INT.lat != 0 and GPS_RAW_INT.alt != 0')
00619 else:
00620 self.recv_match(type='GPS_RAW', blocking=True,
00621 condition='GPS_RAW.fix_type==2 and GPS_RAW.lat != 0 and GPS_RAW.alt != 0')
00622
00623 def location(self, relative_alt=False):
00624 '''return current location'''
00625 self.wait_gps_fix()
00626
00627 self.recv_match(type='VFR_HUD', blocking=True)
00628 self.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
00629 if relative_alt:
00630 alt = self.messages['GLOBAL_POSITION_INT'].relative_alt*0.001
00631 else:
00632 alt = self.messages['VFR_HUD'].alt
00633 return location(self.messages['GPS_RAW_INT'].lat*1.0e-7,
00634 self.messages['GPS_RAW_INT'].lon*1.0e-7,
00635 alt,
00636 self.messages['VFR_HUD'].heading)
00637
00638 def arducopter_arm(self):
00639 '''arm motors (arducopter only)'''
00640 if self.mavlink10():
00641 self.mav.command_long_send(
00642 self.target_system,
00643 self.target_component,
00644 mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
00645 0,
00646 1,
00647 0,
00648 0,
00649 0,
00650 0,
00651 0,
00652 0)
00653
00654 def arducopter_disarm(self):
00655 '''calibrate pressure'''
00656 if self.mavlink10():
00657 self.mav.command_long_send(
00658 self.target_system,
00659 self.target_component,
00660 mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
00661 0,
00662 0,
00663 0,
00664 0,
00665 0,
00666 0,
00667 0,
00668 0)
00669
00670 def motors_armed(self):
00671 '''return true if motors armed'''
00672 if not 'HEARTBEAT' in self.messages:
00673 return False
00674 m = self.messages['HEARTBEAT']
00675 return (m.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 0
00676
00677 def motors_armed_wait(self):
00678 '''wait for motors to be armed'''
00679 while True:
00680 m = self.wait_heartbeat()
00681 if self.motors_armed():
00682 return
00683
00684 def motors_disarmed_wait(self):
00685 '''wait for motors to be disarmed'''
00686 while True:
00687 m = self.wait_heartbeat()
00688 if not self.motors_armed():
00689 return
00690
00691
00692 def field(self, type, field, default=None):
00693 '''convenient function for returning an arbitrary MAVLink
00694 field with a default'''
00695 if not type in self.messages:
00696 return default
00697 return getattr(self.messages[type], field, default)
00698
00699 def param(self, name, default=None):
00700 '''convenient function for returning an arbitrary MAVLink
00701 parameter with a default'''
00702 if not name in self.params:
00703 return default
00704 return self.params[name]
00705
00706 def set_close_on_exec(fd):
00707 '''set the clone on exec flag on a file descriptor. Ignore exceptions'''
00708 try:
00709 import fcntl
00710 flags = fcntl.fcntl(fd, fcntl.F_GETFD)
00711 flags |= fcntl.FD_CLOEXEC
00712 fcntl.fcntl(fd, fcntl.F_SETFD, flags)
00713 except Exception:
00714 pass
00715
00716 class mavserial(mavfile):
00717 '''a serial mavlink port'''
00718 def __init__(self, device, baud=115200, autoreconnect=False, source_system=255, use_native=default_native):
00719 import serial
00720 if ',' in device and not os.path.exists(device):
00721 device, baud = device.split(',')
00722 self.baud = baud
00723 self.device = device
00724 self.autoreconnect = autoreconnect
00725
00726
00727
00728 self.port = serial.Serial(self.device, 1200, timeout=0,
00729 dsrdtr=False, rtscts=False, xonxoff=False)
00730 try:
00731 fd = self.port.fileno()
00732 set_close_on_exec(fd)
00733 except Exception:
00734 fd = None
00735 self.set_baudrate(self.baud)
00736 mavfile.__init__(self, fd, device, source_system=source_system, use_native=use_native)
00737 self.rtscts = False
00738
00739 def set_rtscts(self, enable):
00740 '''enable/disable RTS/CTS if applicable'''
00741 self.port.setRtsCts(enable)
00742 self.rtscts = enable
00743
00744 def set_baudrate(self, baudrate):
00745 '''set baudrate'''
00746 self.port.setBaudrate(baudrate)
00747
00748 def close(self):
00749 self.port.close()
00750
00751 def recv(self,n=None):
00752 if n is None:
00753 n = self.mav.bytes_needed()
00754 if self.fd is None:
00755 waiting = self.port.inWaiting()
00756 if waiting < n:
00757 n = waiting
00758 ret = self.port.read(n)
00759 return ret
00760
00761 def write(self, buf):
00762 try:
00763 return self.port.write(buf)
00764 except Exception:
00765 if not self.portdead:
00766 print("Device %s is dead" % self.device)
00767 self.portdead = True
00768 if self.autoreconnect:
00769 self.reset()
00770 return -1
00771
00772 def reset(self):
00773 import serial
00774 try:
00775 newport = serial.Serial(self.device, self.baud, timeout=0,
00776 dsrdtr=False, rtscts=False, xonxoff=False)
00777 self.port.close()
00778 self.port = newport
00779 print("Device %s reopened OK" % self.device)
00780 self.portdead = False
00781 try:
00782 self.fd = self.port.fileno()
00783 except Exception:
00784 self.fd = None
00785 if self.rtscts:
00786 self.set_rtscts(self.rtscts)
00787 return True
00788 except Exception:
00789 return False
00790
00791
00792 class mavudp(mavfile):
00793 '''a UDP mavlink socket'''
00794 def __init__(self, device, input=True, broadcast=False, source_system=255, use_native=default_native):
00795 a = device.split(':')
00796 if len(a) != 2:
00797 print("UDP ports must be specified as host:port")
00798 sys.exit(1)
00799 self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
00800 self.udp_server = input
00801 if input:
00802 self.port.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
00803 self.port.bind((a[0], int(a[1])))
00804 else:
00805 self.destination_addr = (a[0], int(a[1]))
00806 if broadcast:
00807 self.port.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
00808 set_close_on_exec(self.port.fileno())
00809 self.port.setblocking(0)
00810 self.last_address = None
00811 mavfile.__init__(self, self.port.fileno(), device, source_system=source_system, input=input, use_native=use_native)
00812
00813 def close(self):
00814 self.port.close()
00815
00816 def recv(self,n=None):
00817 try:
00818 data, self.last_address = self.port.recvfrom(300)
00819 except socket.error as e:
00820 if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK, errno.ECONNREFUSED ]:
00821 return ""
00822 raise
00823 return data
00824
00825 def write(self, buf):
00826 try:
00827 if self.udp_server:
00828 if self.last_address:
00829 self.port.sendto(buf, self.last_address)
00830 else:
00831 self.port.sendto(buf, self.destination_addr)
00832 except socket.error:
00833 pass
00834
00835 def recv_msg(self):
00836 '''message receive routine for UDP link'''
00837 self.pre_message()
00838 s = self.recv()
00839 if len(s) == 0:
00840 return None
00841 if self.first_byte:
00842 self.auto_mavlink_version(s)
00843 msg = self.mav.parse_buffer(s)
00844 if msg is not None:
00845 for m in msg:
00846 self.post_message(m)
00847 return msg[0]
00848 return None
00849
00850
00851 class mavtcp(mavfile):
00852 '''a TCP mavlink socket'''
00853 def __init__(self, device, source_system=255, retries=3, use_native=default_native):
00854 a = device.split(':')
00855 if len(a) != 2:
00856 print("TCP ports must be specified as host:port")
00857 sys.exit(1)
00858 self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
00859 self.destination_addr = (a[0], int(a[1]))
00860 while retries >= 0:
00861 retries -= 1
00862 if retries <= 0:
00863 self.port.connect(self.destination_addr)
00864 else:
00865 try:
00866 self.port.connect(self.destination_addr)
00867 break
00868 except Exception as e:
00869 if retries > 0:
00870 print(e, "sleeping")
00871 time.sleep(1)
00872 continue
00873 self.port.setblocking(0)
00874 set_close_on_exec(self.port.fileno())
00875 self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
00876 mavfile.__init__(self, self.port.fileno(), "tcp:" + device, source_system=source_system, use_native=use_native)
00877
00878 def close(self):
00879 self.port.close()
00880
00881 def recv(self,n=None):
00882 if n is None:
00883 n = self.mav.bytes_needed()
00884 try:
00885 data = self.port.recv(n)
00886 except socket.error as e:
00887 if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
00888 return ""
00889 raise
00890 return data
00891
00892 def write(self, buf):
00893 try:
00894 self.port.send(buf)
00895 except socket.error:
00896 pass
00897
00898
00899 class mavlogfile(mavfile):
00900 '''a MAVLink logfile reader/writer'''
00901 def __init__(self, filename, planner_format=None,
00902 write=False, append=False,
00903 robust_parsing=True, notimestamps=False, source_system=255, use_native=default_native):
00904 self.filename = filename
00905 self.writeable = write
00906 self.robust_parsing = robust_parsing
00907 self.planner_format = planner_format
00908 self._two64 = math.pow(2.0, 63)
00909 mode = 'rb'
00910 if self.writeable:
00911 if append:
00912 mode = 'ab'
00913 else:
00914 mode = 'wb'
00915 self.f = open(filename, mode)
00916 self.filesize = os.path.getsize(filename)
00917 self.percent = 0
00918 mavfile.__init__(self, None, filename, source_system=source_system, notimestamps=notimestamps, use_native=use_native)
00919 if self.notimestamps:
00920 self._timestamp = 0
00921 else:
00922 self._timestamp = time.time()
00923 self.stop_on_EOF = True
00924 self._last_message = None
00925 self._last_timestamp = None
00926
00927 def close(self):
00928 self.f.close()
00929
00930 def recv(self,n=None):
00931 if n is None:
00932 n = self.mav.bytes_needed()
00933 return self.f.read(n)
00934
00935 def write(self, buf):
00936 self.f.write(buf)
00937
00938 def scan_timestamp(self, tbuf):
00939 '''scan forward looking in a tlog for a timestamp in a reasonable range'''
00940 while True:
00941 (tusec,) = struct.unpack('>Q', tbuf)
00942 t = tusec * 1.0e-6
00943 if abs(t - self._last_timestamp) <= 3*24*60*60:
00944 break
00945 c = self.f.read(1)
00946 if len(c) != 1:
00947 break
00948 tbuf = tbuf[1:] + c
00949 return t
00950
00951
00952 def pre_message(self):
00953 '''read timestamp if needed'''
00954
00955 if self.filesize != 0:
00956 self.percent = (100.0 * self.f.tell()) / self.filesize
00957 if self.notimestamps:
00958 return
00959 if self.planner_format:
00960 tbuf = self.f.read(21)
00961 if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':':
00962 raise RuntimeError('bad planner timestamp %s' % tbuf)
00963 hnsec = self._two64 + float(tbuf[0:20])
00964 t = hnsec * 1.0e-7
00965 t -= 719163 * 24 * 60 * 60
00966 self._link = 0
00967 else:
00968 tbuf = self.f.read(8)
00969 if len(tbuf) != 8:
00970 return
00971 (tusec,) = struct.unpack('>Q', tbuf)
00972 t = tusec * 1.0e-6
00973 if (self._last_timestamp is not None and
00974 self._last_message.get_type() == "BAD_DATA" and
00975 abs(t - self._last_timestamp) > 3*24*60*60):
00976 t = self.scan_timestamp(tbuf)
00977 self._link = tusec & 0x3
00978 self._timestamp = t
00979
00980 def post_message(self, msg):
00981 '''add timestamp to message'''
00982
00983 super(mavlogfile, self).post_message(msg)
00984 if self.planner_format:
00985 self.f.read(1)
00986 self.timestamp = msg._timestamp
00987 self._last_message = msg
00988 if msg.get_type() != "BAD_DATA":
00989 self._last_timestamp = msg._timestamp
00990
00991
00992 class mavmemlog(mavfile):
00993 '''a MAVLink log in memory. This allows loading a log into
00994 memory to make it easier to do multiple sweeps over a log'''
00995 def __init__(self, mav):
00996 mavfile.__init__(self, None, 'memlog')
00997 self._msgs = []
00998 self._index = 0
00999 self._count = 0
01000 while True:
01001 m = mav.recv_msg()
01002 if m is None:
01003 break
01004 self._msgs.append(m)
01005 self._count = len(self._msgs)
01006
01007 def recv_msg(self):
01008 '''message receive routine'''
01009 if self._index >= self._count:
01010 return None
01011 m = self._msgs[self._index]
01012 self._index += 1
01013 self.percent = (100.0 * self._index) / self._count
01014 return m
01015
01016 def rewind(self):
01017 '''rewind to start'''
01018 self._index = 0
01019 self.percent = 0
01020
01021 class mavchildexec(mavfile):
01022 '''a MAVLink child processes reader/writer'''
01023 def __init__(self, filename, source_system=255, use_native=default_native):
01024 from subprocess import Popen, PIPE
01025 import fcntl
01026
01027 self.filename = filename
01028 self.child = Popen(filename, shell=False, stdout=PIPE, stdin=PIPE, bufsize=0)
01029 self.fd = self.child.stdout.fileno()
01030
01031 fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
01032 fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
01033
01034 fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL)
01035 fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK)
01036
01037 mavfile.__init__(self, self.fd, filename, source_system=source_system, use_native=use_native)
01038
01039 def close(self):
01040 self.child.close()
01041
01042 def recv(self,n=None):
01043 try:
01044 x = self.child.stdout.read(1)
01045 except Exception:
01046 return ''
01047 return x
01048
01049 def write(self, buf):
01050 self.child.stdin.write(buf)
01051
01052
01053 def mavlink_connection(device, baud=115200, source_system=255,
01054 planner_format=None, write=False, append=False,
01055 robust_parsing=True, notimestamps=False, input=True,
01056 dialect=None, autoreconnect=False, zero_time_base=False,
01057 retries=3, use_native=default_native):
01058 '''open a serial, UDP, TCP or file mavlink connection'''
01059 global mavfile_global
01060
01061 if dialect is not None:
01062 set_dialect(dialect)
01063 if device.startswith('tcp:'):
01064 return mavtcp(device[4:], source_system=source_system, retries=retries, use_native=use_native)
01065 if device.startswith('udpin:'):
01066 return mavudp(device[6:], input=True, source_system=source_system, use_native=use_native)
01067 if device.startswith('udpout:'):
01068 return mavudp(device[7:], input=False, source_system=source_system, use_native=use_native)
01069
01070 if device.startswith('udp:'):
01071 return mavudp(device[4:], input=input, source_system=source_system, use_native=use_native)
01072
01073 if device.lower().endswith('.bin') or device.lower().endswith('.px4log'):
01074
01075 from pymavlink import DFReader
01076 m = DFReader.DFReader_binary(device, zero_time_base=zero_time_base)
01077 mavfile_global = m
01078 return m
01079
01080 if device.endswith('.log'):
01081
01082 from pymavlink import DFReader
01083 if DFReader.DFReader_is_text_log(device):
01084 m = DFReader.DFReader_text(device, zero_time_base=zero_time_base)
01085 mavfile_global = m
01086 return m
01087
01088
01089 logsuffixes = ['mavlink', 'log', 'raw', 'tlog' ]
01090 suffix = device.split('.')[-1].lower()
01091 if device.find(':') != -1 and not suffix in logsuffixes:
01092 return mavudp(device, source_system=source_system, input=input, use_native=use_native)
01093 if os.path.isfile(device):
01094 if device.endswith(".elf") or device.find("/bin/") != -1:
01095 print("executing '%s'" % device)
01096 return mavchildexec(device, source_system=source_system, use_native=use_native)
01097 else:
01098 return mavlogfile(device, planner_format=planner_format, write=write,
01099 append=append, robust_parsing=robust_parsing, notimestamps=notimestamps,
01100 source_system=source_system, use_native=use_native)
01101 return mavserial(device, baud=baud, source_system=source_system, autoreconnect=autoreconnect, use_native=use_native)
01102
01103 class periodic_event(object):
01104 '''a class for fixed frequency events'''
01105 def __init__(self, frequency):
01106 self.frequency = float(frequency)
01107 self.last_time = time.time()
01108
01109 def force(self):
01110 '''force immediate triggering'''
01111 self.last_time = 0
01112
01113 def trigger(self):
01114 '''return True if we should trigger now'''
01115 tnow = time.time()
01116
01117 if tnow < self.last_time:
01118 print("Warning, time moved backwards. Restarting timer.")
01119 self.last_time = tnow
01120
01121 if self.last_time + (1.0/self.frequency) <= tnow:
01122 self.last_time = tnow
01123 return True
01124 return False
01125
01126
01127 try:
01128 from curses import ascii
01129 have_ascii = True
01130 except:
01131 have_ascii = False
01132
01133 def is_printable(c):
01134 '''see if a character is printable'''
01135 global have_ascii
01136 if have_ascii:
01137 return ascii.isprint(c)
01138 if isinstance(c, int):
01139 ic = c
01140 else:
01141 ic = ord(c)
01142 return ic >= 32 and ic <= 126
01143
01144 def all_printable(buf):
01145 '''see if a string is all printable'''
01146 for c in buf:
01147 if not is_printable(c) and not c in ['\r', '\n', '\t']:
01148 return False
01149 return True
01150
01151 class SerialPort(object):
01152 '''auto-detected serial port'''
01153 def __init__(self, device, description=None, hwid=None):
01154 self.device = device
01155 self.description = description
01156 self.hwid = hwid
01157
01158 def __str__(self):
01159 ret = self.device
01160 if self.description is not None:
01161 ret += " : " + self.description
01162 if self.hwid is not None:
01163 ret += " : " + self.hwid
01164 return ret
01165
01166 def auto_detect_serial_win32(preferred_list=['*']):
01167 '''try to auto-detect serial ports on win32'''
01168 try:
01169 from serial.tools.list_ports_windows import comports
01170 list = sorted(comports())
01171 except:
01172 return []
01173 ret = []
01174 others = []
01175 for port, description, hwid in list:
01176 matches = False
01177 p = SerialPort(port, description=description, hwid=hwid)
01178 for preferred in preferred_list:
01179 if fnmatch.fnmatch(description, preferred) or fnmatch.fnmatch(hwid, preferred):
01180 matches = True
01181 if matches:
01182 ret.append(p)
01183 else:
01184 others.append(p)
01185 if len(ret) > 0:
01186 return ret
01187
01188 ret.extend(others)
01189 return ret
01190
01191
01192
01193
01194 def auto_detect_serial_unix(preferred_list=['*']):
01195 '''try to auto-detect serial ports on unix'''
01196 import glob
01197 glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*')
01198 ret = []
01199 others = []
01200
01201 for d in glist:
01202 matches = False
01203 for preferred in preferred_list:
01204 if fnmatch.fnmatch(d, preferred):
01205 matches = True
01206 if matches:
01207 ret.append(SerialPort(d))
01208 else:
01209 others.append(SerialPort(d))
01210 if len(ret) > 0:
01211 return ret
01212 ret.extend(others)
01213 return ret
01214
01215 def auto_detect_serial(preferred_list=['*']):
01216 '''try to auto-detect serial port'''
01217
01218 if os.name == 'nt':
01219 return auto_detect_serial_win32(preferred_list=preferred_list)
01220 return auto_detect_serial_unix(preferred_list=preferred_list)
01221
01222 def mode_string_v09(msg):
01223 '''mode string for 0.9 protocol'''
01224 mode = msg.mode
01225 nav_mode = msg.nav_mode
01226
01227 MAV_MODE_UNINIT = 0
01228 MAV_MODE_MANUAL = 2
01229 MAV_MODE_GUIDED = 3
01230 MAV_MODE_AUTO = 4
01231 MAV_MODE_TEST1 = 5
01232 MAV_MODE_TEST2 = 6
01233 MAV_MODE_TEST3 = 7
01234
01235 MAV_NAV_GROUNDED = 0
01236 MAV_NAV_LIFTOFF = 1
01237 MAV_NAV_HOLD = 2
01238 MAV_NAV_WAYPOINT = 3
01239 MAV_NAV_VECTOR = 4
01240 MAV_NAV_RETURNING = 5
01241 MAV_NAV_LANDING = 6
01242 MAV_NAV_LOST = 7
01243 MAV_NAV_LOITER = 8
01244
01245 cmode = (mode, nav_mode)
01246 mapping = {
01247 (MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING",
01248 (MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL",
01249 (MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE",
01250 (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
01251 (MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE",
01252 (MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA",
01253 (MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO",
01254 (MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL",
01255 (MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER",
01256 (MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF",
01257 (MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING",
01258 (MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER",
01259 (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED",
01260 (MAV_MODE_GUIDED, MAV_NAV_WAYPOINT) : "GUIDED",
01261 (100, MAV_NAV_VECTOR) : "STABILIZE",
01262 (101, MAV_NAV_VECTOR) : "ACRO",
01263 (102, MAV_NAV_VECTOR) : "ALT_HOLD",
01264 (107, MAV_NAV_VECTOR) : "CIRCLE",
01265 (109, MAV_NAV_VECTOR) : "LAND",
01266 }
01267 if cmode in mapping:
01268 return mapping[cmode]
01269 return "Mode(%s,%s)" % cmode
01270
01271 mode_mapping_apm = {
01272 0 : 'MANUAL',
01273 1 : 'CIRCLE',
01274 2 : 'STABILIZE',
01275 3 : 'TRAINING',
01276 4 : 'ACRO',
01277 5 : 'FBWA',
01278 6 : 'FBWB',
01279 7 : 'CRUISE',
01280 8 : 'AUTOTUNE',
01281 10 : 'AUTO',
01282 11 : 'RTL',
01283 12 : 'LOITER',
01284 14 : 'LAND',
01285 15 : 'GUIDED',
01286 16 : 'INITIALISING'
01287 }
01288 mode_mapping_acm = {
01289 0 : 'STABILIZE',
01290 1 : 'ACRO',
01291 2 : 'ALT_HOLD',
01292 3 : 'AUTO',
01293 4 : 'GUIDED',
01294 5 : 'LOITER',
01295 6 : 'RTL',
01296 7 : 'CIRCLE',
01297 8 : 'POSITION',
01298 9 : 'LAND',
01299 10 : 'OF_LOITER',
01300 11 : 'DRIFT',
01301 13 : 'SPORT',
01302 14 : 'FLIP',
01303 15 : 'AUTOTUNE',
01304 16 : 'POSHOLD'
01305 }
01306 mode_mapping_rover = {
01307 0 : 'MANUAL',
01308 2 : 'LEARNING',
01309 3 : 'STEERING',
01310 4 : 'HOLD',
01311 10 : 'AUTO',
01312 11 : 'RTL',
01313 15 : 'GUIDED',
01314 16 : 'INITIALISING'
01315 }
01316
01317 mode_mapping_tracker = {
01318 0 : 'MANUAL',
01319 1 : 'STOP',
01320 2 : 'SCAN',
01321 10 : 'AUTO',
01322 16 : 'INITIALISING'
01323 }
01324
01325 mode_mapping_px4 = {
01326 0 : 'MANUAL',
01327 1 : 'ATTITUDE',
01328 2 : 'EASY',
01329 3 : 'AUTO'
01330 }
01331
01332
01333 def mode_mapping_byname(mav_type):
01334 '''return dictionary mapping mode names to numbers, or None if unknown'''
01335 map = None
01336 if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
01337 mavlink.MAV_TYPE_HELICOPTER,
01338 mavlink.MAV_TYPE_HEXAROTOR,
01339 mavlink.MAV_TYPE_OCTOROTOR,
01340 mavlink.MAV_TYPE_TRICOPTER]:
01341 map = mode_mapping_acm
01342 if mav_type == mavlink.MAV_TYPE_FIXED_WING:
01343 map = mode_mapping_apm
01344 if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
01345 map = mode_mapping_rover
01346 if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
01347 map = mode_mapping_tracker
01348 if map is None:
01349 return None
01350 inv_map = dict((a, b) for (b, a) in map.items())
01351 return inv_map
01352
01353 def mode_mapping_bynumber(mav_type):
01354 '''return dictionary mapping mode numbers to name, or None if unknown'''
01355 map = None
01356 if mav_type in [mavlink.MAV_TYPE_QUADROTOR,
01357 mavlink.MAV_TYPE_HELICOPTER,
01358 mavlink.MAV_TYPE_HEXAROTOR,
01359 mavlink.MAV_TYPE_OCTOROTOR,
01360 mavlink.MAV_TYPE_TRICOPTER]:
01361 map = mode_mapping_acm
01362 if mav_type == mavlink.MAV_TYPE_FIXED_WING:
01363 map = mode_mapping_apm
01364 if mav_type == mavlink.MAV_TYPE_GROUND_ROVER:
01365 map = mode_mapping_rover
01366 if mav_type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
01367 map = mode_mapping_tracker
01368 if map is None:
01369 return None
01370 return map
01371
01372
01373 def mode_string_v10(msg):
01374 '''mode string for 1.0 protocol, from heartbeat'''
01375 if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED:
01376 return "Mode(0x%08x)" % msg.base_mode
01377 if msg.type in [ mavlink.MAV_TYPE_QUADROTOR, mavlink.MAV_TYPE_HEXAROTOR,
01378 mavlink.MAV_TYPE_OCTOROTOR, mavlink.MAV_TYPE_TRICOPTER,
01379 mavlink.MAV_TYPE_COAXIAL,
01380 mavlink.MAV_TYPE_HELICOPTER ]:
01381 if msg.custom_mode in mode_mapping_acm:
01382 return mode_mapping_acm[msg.custom_mode]
01383 if msg.type == mavlink.MAV_TYPE_FIXED_WING:
01384 if msg.custom_mode in mode_mapping_apm:
01385 return mode_mapping_apm[msg.custom_mode]
01386 if msg.type == mavlink.MAV_TYPE_GROUND_ROVER:
01387 if msg.custom_mode in mode_mapping_rover:
01388 return mode_mapping_rover[msg.custom_mode]
01389 if msg.type == mavlink.MAV_TYPE_ANTENNA_TRACKER:
01390 if msg.custom_mode in mode_mapping_tracker:
01391 return mode_mapping_tracker[msg.custom_mode]
01392 return "Mode(%u)" % msg.custom_mode
01393
01394 def mode_string_apm(mode_number):
01395 '''return mode string for APM:Plane'''
01396 if mode_number in mode_mapping_apm:
01397 return mode_mapping_apm[mode_number]
01398 return "Mode(%u)" % mode_number
01399
01400 def mode_string_acm(mode_number):
01401 '''return mode string for APM:Copter'''
01402 if mode_number in mode_mapping_acm:
01403 return mode_mapping_acm[mode_number]
01404 return "Mode(%u)" % mode_number
01405
01406 def mode_string_px4(mode_number):
01407 '''return mode string for PX4 flight stack'''
01408 if mode_number in mode_mapping_px4:
01409 return mode_mapping_px4[mode_number]
01410 return "Mode(%u)" % mode_number
01411
01412 class x25crc(object):
01413 '''x25 CRC - based on checksum.h from mavlink library'''
01414 def __init__(self, buf=''):
01415 self.crc = 0xffff
01416 self.accumulate(buf)
01417
01418 def accumulate(self, buf):
01419 '''add in some more bytes'''
01420 bytes = array.array('B')
01421 if isinstance(buf, array.array):
01422 bytes.extend(buf)
01423 else:
01424 bytes.fromstring(buf)
01425 accum = self.crc
01426 for b in bytes:
01427 tmp = b ^ (accum & 0xff)
01428 tmp = (tmp ^ (tmp<<4)) & 0xFF
01429 accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4)
01430 accum = accum & 0xFFFF
01431 self.crc = accum
01432
01433 class MavlinkSerialPort():
01434 '''an object that looks like a serial port, but
01435 transmits using mavlink SERIAL_CONTROL packets'''
01436 def __init__(self, portname, baudrate, devnum=0, devbaud=0, timeout=3, debug=0):
01437 from . import mavutil
01438
01439 self.baudrate = 0
01440 self.timeout = timeout
01441 self._debug = debug
01442 self.buf = ''
01443 self.port = devnum
01444 self.debug("Connecting with MAVLink to %s ..." % portname)
01445 self.mav = mavutil.mavlink_connection(portname, autoreconnect=True, baud=baudrate)
01446 self.mav.wait_heartbeat()
01447 self.debug("HEARTBEAT OK\n")
01448 if devbaud != 0:
01449 self.setBaudrate(devbaud)
01450 self.debug("Locked serial device\n")
01451
01452 def debug(self, s, level=1):
01453 '''write some debug text'''
01454 if self._debug >= level:
01455 print(s)
01456
01457 def write(self, b):
01458 '''write some bytes'''
01459 from . import mavutil
01460 self.debug("sending '%s' (0x%02x) of len %u\n" % (b, ord(b[0]), len(b)), 2)
01461 while len(b) > 0:
01462 n = len(b)
01463 if n > 70:
01464 n = 70
01465 buf = [ord(x) for x in b[:n]]
01466 buf.extend([0]*(70-len(buf)))
01467 self.mav.mav.serial_control_send(self.port,
01468 mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
01469 mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND,
01470 0,
01471 0,
01472 n,
01473 buf)
01474 b = b[n:]
01475
01476 def _recv(self):
01477 '''read some bytes into self.buf'''
01478 from . import mavutil
01479 start_time = time.time()
01480 while time.time() < start_time + self.timeout:
01481 m = self.mav.recv_match(condition='SERIAL_CONTROL.count!=0',
01482 type='SERIAL_CONTROL', blocking=False, timeout=0)
01483 if m is not None and m.count != 0:
01484 break
01485 self.mav.mav.serial_control_send(self.port,
01486 mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
01487 mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND,
01488 0,
01489 0,
01490 0, [0]*70)
01491 m = self.mav.recv_match(condition='SERIAL_CONTROL.count!=0',
01492 type='SERIAL_CONTROL', blocking=True, timeout=0.01)
01493 if m is not None and m.count != 0:
01494 break
01495 if m is not None:
01496 if self._debug > 2:
01497 print(m)
01498 data = m.data[:m.count]
01499 self.buf += ''.join(str(chr(x)) for x in data)
01500
01501 def read(self, n):
01502 '''read some bytes'''
01503 if len(self.buf) == 0:
01504 self._recv()
01505 if len(self.buf) > 0:
01506 if n > len(self.buf):
01507 n = len(self.buf)
01508 ret = self.buf[:n]
01509 self.buf = self.buf[n:]
01510 if self._debug >= 2:
01511 for b in ret:
01512 self.debug("read 0x%x" % ord(b), 2)
01513 return ret
01514 return ''
01515
01516 def flushInput(self):
01517 '''flush any pending input'''
01518 self.buf = ''
01519 saved_timeout = self.timeout
01520 self.timeout = 0.5
01521 self._recv()
01522 self.timeout = saved_timeout
01523 self.buf = ''
01524 self.debug("flushInput")
01525
01526 def setBaudrate(self, baudrate):
01527 '''set baudrate'''
01528 from . import mavutil
01529 if self.baudrate == baudrate:
01530 return
01531 self.baudrate = baudrate
01532 self.mav.mav.serial_control_send(self.port,
01533 mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE,
01534 0,
01535 self.baudrate,
01536 0, [0]*70)
01537 self.flushInput()
01538 self.debug("Changed baudrate %u" % self.baudrate)
01539
01540 if __name__ == '__main__':
01541 serial_list = auto_detect_serial(preferred_list=['*FTDI*',"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*'])
01542 for port in serial_list:
01543 print("%s" % port)