Public Member Functions | Public Attributes | Private Attributes
pymavlink.mavutil.mavfile Class Reference
Inheritance diagram for pymavlink.mavutil.mavfile:
Inheritance graph
[legend]

List of all members.

Public Member Functions

def __init__
def arducopter_arm
def arducopter_disarm
def auto_mavlink_version
def calibrate_level
def calibrate_pressure
def check_condition
def close
def disable_signing
def field
def location
def mavlink10
def mavlink20
def mode_mapping
def motors_armed
def motors_armed_wait
def motors_disarmed_wait
def packet_loss
def param
def param_fetch_all
def param_fetch_one
def param_set_send
def post_message
def pre_message
def reboot_autopilot
def recv
def recv_match
def recv_msg
def select
def set_mode
def set_mode_auto
def set_mode_fbwa
def set_mode_flag
def set_mode_loiter
def set_mode_manual
def set_mode_rtl
def set_relay
def set_rtscts
def set_servo
def setup_logfile
def setup_logfile_raw
def setup_signing
def time_since
def wait_gps_fix
def wait_heartbeat
def waypoint_clear_all_send
def waypoint_count_send
def waypoint_current
def waypoint_request_list_send
def waypoint_request_send
def waypoint_set_current_send
def write

Public Attributes

 address
 altitude
 base_mode
 fd
 first_byte
 flightmode
 ground_pressure
 ground_temperature
 idle_hooks
 last_seq
 logfile
 logfile_raw
 mav
 mav_count
 mav_loss
 mav_type
 message_hooks
 messages
 notimestamps
 param_fetch_complete
 param_fetch_in_progress
 param_fetch_start
 params
 portdead
 robust_parsing
 source_system
 start_time
 stop_on_EOF
 target_component
 target_system
 timestamp
 uptime
 vehicle_type
 WIRE_PROTOCOL_VERSION

Private Attributes

 _timestamp

Detailed Description

a generic mavlink port

Definition at line 109 of file mavutil.py.


Constructor & Destructor Documentation

def pymavlink.mavutil.mavfile.__init__ (   self,
  fd,
  address,
  source_system = 255,
  notimestamps = False,
  input = True,
  use_native = default_native 
)

Definition at line 111 of file mavutil.py.


Member Function Documentation

arm motors (arducopter only)

Definition at line 649 of file mavutil.py.

calibrate pressure

Definition at line 665 of file mavutil.py.

auto-switch mavlink protocol version

Definition at line 156 of file mavutil.py.

calibrate accels (1D version)

Definition at line 593 of file mavutil.py.

calibrate pressure

Definition at line 599 of file mavutil.py.

def pymavlink.mavutil.mavfile.check_condition (   self,
  condition 
)
check if a condition is true

Definition at line 363 of file mavutil.py.

def pymavlink.mavutil.mavfile.close (   self,
  n = None 
)
default close method

Definition at line 196 of file mavutil.py.

disable MAVLink2 signing

Definition at line 737 of file mavutil.py.

def pymavlink.mavutil.mavfile.field (   self,
  type,
  field,
  default = None 
)
convenient function for returning an arbitrary MAVLink
   field with a default

Definition at line 703 of file mavutil.py.

def pymavlink.mavutil.mavfile.location (   self,
  relative_alt = False 
)
return current location

Definition at line 634 of file mavutil.py.

return True if using MAVLink 1.0 or later

Definition at line 367 of file mavutil.py.

return True if using MAVLink 2.0 or later

Definition at line 371 of file mavutil.py.

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

Definition at line 493 of file mavutil.py.

return true if motors armed

Definition at line 681 of file mavutil.py.

wait for motors to be armed

Definition at line 688 of file mavutil.py.

wait for motors to be disarmed

Definition at line 695 of file mavutil.py.

packet loss as a percentage

Definition at line 297 of file mavutil.py.

def pymavlink.mavutil.mavfile.param (   self,
  name,
  default = None 
)
convenient function for returning an arbitrary MAVLink
   parameter with a default

Definition at line 710 of file mavutil.py.

initiate fetch of all parameters

Definition at line 387 of file mavutil.py.

def pymavlink.mavutil.mavfile.param_fetch_one (   self,
  name 
)
initiate fetch of one parameter

Definition at line 396 of file mavutil.py.

def pymavlink.mavutil.mavfile.param_set_send (   self,
  parm_name,
  parm_value,
  parm_type = None 
)
wrapper for parameter set

Definition at line 410 of file mavutil.py.

def pymavlink.mavutil.mavfile.post_message (   self,
  msg 
)
default post message call

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 224 of file mavutil.py.

default pre message call

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 216 of file mavutil.py.

def pymavlink.mavutil.mavfile.reboot_autopilot (   self,
  hold_in_bootloader = False 
)
reboot the autopilot

Definition at line 609 of file mavutil.py.

def pymavlink.mavutil.mavfile.recv (   self,
  n = None 
)
def pymavlink.mavutil.mavfile.recv_match (   self,
  condition = None,
  type = None,
  blocking = False,
  timeout = None 
)
recv the next MAVLink message that matches the given condition
type can be a string or a list of strings

Definition at line 333 of file mavutil.py.

message receive routine

Reimplemented in pymavlink.mavutil.mavmemlog, and pymavlink.mavutil.mavudp.

Definition at line 304 of file mavutil.py.

def pymavlink.mavutil.mavfile.select (   self,
  timeout 
)
wait for up to timeout seconds for more data

Definition at line 205 of file mavutil.py.

def pymavlink.mavutil.mavfile.set_mode (   self,
  mode 
)
enter arbitrary mode

Definition at line 516 of file mavutil.py.

enter auto mode

Definition at line 484 of file mavutil.py.

enter FBWA mode

Definition at line 548 of file mavutil.py.

def pymavlink.mavutil.mavfile.set_mode_flag (   self,
  flag,
  enable 
)
Enables/ disables MAV_MODE_FLAG
@param flag The mode flag, 
  see MAV_MODE_FLAG enum
@param enable Enable the flag, (True/False)

Definition at line 464 of file mavutil.py.

enter LOITER mode

Definition at line 558 of file mavutil.py.

enter MANUAL mode

Definition at line 537 of file mavutil.py.

enter RTL mode

Definition at line 528 of file mavutil.py.

def pymavlink.mavutil.mavfile.set_relay (   self,
  relay_pin = 0,
  state = True 
)
Set relay_pin to value of state

Definition at line 575 of file mavutil.py.

def pymavlink.mavutil.mavfile.set_rtscts (   self,
  enable 
)
enable/disable RTS/CTS if applicable

Reimplemented in pymavlink.mavutil.mavserial.

Definition at line 220 of file mavutil.py.

def pymavlink.mavutil.mavfile.set_servo (   self,
  channel,
  pwm 
)
set a servo value

Definition at line 567 of file mavutil.py.

def pymavlink.mavutil.mavfile.setup_logfile (   self,
  logfile,
  mode = 'w' 
)
start logging to the given logfile, with timestamps

Definition at line 375 of file mavutil.py.

def pymavlink.mavutil.mavfile.setup_logfile_raw (   self,
  logfile,
  mode = 'w' 
)
start logging raw bytes to the given logfile, without timestamps

Definition at line 379 of file mavutil.py.

def pymavlink.mavutil.mavfile.setup_signing (   self,
  secret_key,
  sign_outgoing = True,
  allow_unsigned_callback = None,
  initial_timestamp = None,
  link_id = None 
)
setup for MAVLink2 signing

Definition at line 717 of file mavutil.py.

def pymavlink.mavutil.mavfile.time_since (   self,
  mtype 
)
return the time since the last message of type mtype was received

Definition at line 404 of file mavutil.py.

Definition at line 625 of file mavutil.py.

def pymavlink.mavutil.mavfile.wait_heartbeat (   self,
  blocking = True 
)
wait for a heartbeat so we know the target system IDs

Definition at line 383 of file mavutil.py.

wrapper for waypoint_clear_all_send

Definition at line 428 of file mavutil.py.

wrapper for waypoint_count_send

Definition at line 457 of file mavutil.py.

return current waypoint

Definition at line 449 of file mavutil.py.

wrapper for waypoint_request_list_send

Definition at line 421 of file mavutil.py.

wrapper for waypoint_request_send

Definition at line 435 of file mavutil.py.

wrapper for waypoint_set_current_send

Definition at line 442 of file mavutil.py.

def pymavlink.mavutil.mavfile.write (   self,
  buf 
)

Member Data Documentation

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Reimplemented in pymavlink.mavutil.mavmemlog.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 387 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Reimplemented in pymavlink.mavutil.mavserial.

Definition at line 111 of file mavutil.py.

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Reimplemented in pymavlink.mavutil.mavlogfile.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.

Definition at line 111 of file mavutil.py.


The documentation for this class was generated from the following file:


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