Classes | Functions | Variables
pymavlink::mavutil Namespace Reference

Classes

class  location
class  mavchildexec
class  mavfile
class  MavlinkSerialPort
class  mavlogfile
class  mavmemlog
class  mavserial
class  mavtcp
class  mavtcpin
class  mavudp
class  periodic_event
class  SerialPort
class  x25crc

Functions

def all_printable
def auto_detect_serial
def auto_detect_serial_unix
def auto_detect_serial_win32
def evaluate_condition
def evaluate_expression
def is_printable
def mavlink10
def mavlink20
def mavlink_connection
def mode_mapping_byname
def mode_mapping_bynumber
def mode_string_acm
def mode_string_apm
def mode_string_px4
def mode_string_v09
def mode_string_v10
def set_close_on_exec
def set_dialect

Variables

 default_native = False
int global_link_id = 0
 mavfile_global = None
 mavlink = None
dictionary mode_mapping_acm
dictionary mode_mapping_apm
dictionary mode_mapping_px4
dictionary mode_mapping_rover
dictionary mode_mapping_tracker
tuple serial_list = auto_detect_serial(preferred_list=['*FTDI*',"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*'])
int UDP_MAX_PACKET_LEN = 65535

Function Documentation

see if a string is all printable

Definition at line 1260 of file mavutil.py.

def pymavlink.mavutil.auto_detect_serial (   preferred_list = ['*'])
try to auto-detect serial port

Definition at line 1331 of file mavutil.py.

def pymavlink.mavutil.auto_detect_serial_unix (   preferred_list = ['*'])
try to auto-detect serial ports on unix

Definition at line 1310 of file mavutil.py.

def pymavlink.mavutil.auto_detect_serial_win32 (   preferred_list = ['*'])
try to auto-detect serial ports on win32

Definition at line 1282 of file mavutil.py.

def pymavlink.mavutil.evaluate_condition (   condition,
  vars 
)
evaluation a conditional (boolean) statement

Definition at line 54 of file mavutil.py.

def pymavlink.mavutil.evaluate_expression (   expression,
  vars 
)
evaluation an expression

Definition at line 50 of file mavutil.py.

see if a character is printable

Definition at line 1249 of file mavutil.py.

return True if using MAVLink 1.0 or later

Definition at line 42 of file mavutil.py.

return True if using MAVLink 2.0

Definition at line 46 of file mavutil.py.

def pymavlink.mavutil.mavlink_connection (   device,
  baud = 115200,
  source_system = 255,
  planner_format = None,
  write = False,
  append = False,
  robust_parsing = True,
  notimestamps = False,
  input = True,
  dialect = None,
  autoreconnect = False,
  zero_time_base = False,
  retries = 3,
  use_native = default_native 
)
open a serial, UDP, TCP or file mavlink connection

Definition at line 1165 of file mavutil.py.

return dictionary mapping mode names to numbers, or None if unknown

Definition at line 1454 of file mavutil.py.

return dictionary mapping mode numbers to name, or None if unknown

Definition at line 1474 of file mavutil.py.

def pymavlink.mavutil.mode_string_acm (   mode_number)
return mode string for APM:Copter

Definition at line 1521 of file mavutil.py.

def pymavlink.mavutil.mode_string_apm (   mode_number)
return mode string for APM:Plane

Definition at line 1515 of file mavutil.py.

def pymavlink.mavutil.mode_string_px4 (   mode_number)
return mode string for PX4 flight stack

Definition at line 1527 of file mavutil.py.

mode string for 0.9 protocol

Definition at line 1338 of file mavutil.py.

mode string for 1.0 protocol, from heartbeat

Definition at line 1494 of file mavutil.py.

set the clone on exec flag on a file descriptor. Ignore exceptions

Definition at line 745 of file mavutil.py.

def pymavlink.mavutil.set_dialect (   dialect)
set the MAVLink dialect to work with.
For example, set_dialect("ardupilotmega")

Definition at line 74 of file mavutil.py.


Variable Documentation

Definition at line 33 of file mavutil.py.

Definition at line 36 of file mavutil.py.

Definition at line 30 of file mavutil.py.

Definition at line 26 of file mavutil.py.

Initial value:
00001 {
00002     0 : 'STABILIZE',
00003     1 : 'ACRO',
00004     2 : 'ALT_HOLD',
00005     3 : 'AUTO',
00006     4 : 'GUIDED',
00007     5 : 'LOITER',
00008     6 : 'RTL',
00009     7 : 'CIRCLE',
00010     8 : 'POSITION',
00011     9 : 'LAND',
00012     10 : 'OF_LOITER',
00013     11 : 'DRIFT',
00014     13 : 'SPORT',
00015     14 : 'FLIP',
00016     15 : 'AUTOTUNE',
00017     16 : 'POSHOLD'
00018     }

Definition at line 1409 of file mavutil.py.

Initial value:
00001 {
00002     0 : 'MANUAL',
00003     1 : 'CIRCLE',
00004     2 : 'STABILIZE',
00005     3 : 'TRAINING',
00006     4 : 'ACRO',
00007     5 : 'FBWA',
00008     6 : 'FBWB',
00009     7 : 'CRUISE',
00010     8 : 'AUTOTUNE',
00011     10 : 'AUTO',
00012     11 : 'RTL',
00013     12 : 'LOITER',
00014     14 : 'LAND',
00015     15 : 'GUIDED',
00016     16 : 'INITIALISING',
00017     17 : 'QSTABILIZE',
00018     18 : 'QHOVER',
00019     19 : 'QLOITER',
00020     20 : 'QLAND',
00021     21 : 'QRTL',
00022     }

Definition at line 1387 of file mavutil.py.

Initial value:
00001 {
00002     0 : 'MANUAL',
00003     1 : 'ATTITUDE',
00004     2 : 'EASY',
00005     3 : 'AUTO'
00006     }

Definition at line 1446 of file mavutil.py.

Initial value:
00001 {
00002     0 : 'MANUAL',
00003     2 : 'LEARNING',
00004     3 : 'STEERING',
00005     4 : 'HOLD',
00006     10 : 'AUTO',
00007     11 : 'RTL',
00008     15 : 'GUIDED',
00009     16 : 'INITIALISING'
00010     }

Definition at line 1427 of file mavutil.py.

Initial value:
00001 {
00002     0 : 'MANUAL',
00003     1 : 'STOP',
00004     2 : 'SCAN',
00005     10 : 'AUTO',
00006     16 : 'INITIALISING'
00007     }

Definition at line 1438 of file mavutil.py.

tuple pymavlink::mavutil::serial_list = auto_detect_serial(preferred_list=['*FTDI*',"*Arduino_Mega_2560*", "*3D_Robotics*", "*USB_to_UART*", '*PX4*', '*FMU*'])

Definition at line 1662 of file mavutil.py.

Definition at line 22 of file mavutil.py.



mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57