m.MAVLink(object) : class documentation

Part of mavlink View In Hierarchy

MAVLink protocol handling class
Method __init__ Undocumented
Method set_callback Undocumented
Method send send a MAVLink message
Method bytes_needed return number of bytes needed for next parsing stage
Method parse_char input some data bytes, possibly returning a new message
Method decode decode a buffer as a MAVLink message
Method heartbeat_encode The heartbeat message shows that a system is present and responding.
Method heartbeat_send The heartbeat message shows that a system is present and responding.
Method boot_encode The boot message indicates that a system is starting. The onboard
Method boot_send The boot message indicates that a system is starting. The onboard
Method system_time_encode The system time is the time of the master clock, typically the
Method system_time_send The system time is the time of the master clock, typically the
Method ping_encode A ping message either requesting or responding to a ping. This allows
Method ping_send A ping message either requesting or responding to a ping. This allows
Method system_time_utc_encode UTC date and time from GPS module
Method system_time_utc_send UTC date and time from GPS module
Method change_operator_control_encode Request to control this MAV
Method change_operator_control_send Request to control this MAV
Method change_operator_control_ack_encode Accept / deny control of this MAV
Method change_operator_control_ack_send Accept / deny control of this MAV
Method auth_key_encode Emit an encrypted signature / key identifying this system. PLEASE
Method auth_key_send Emit an encrypted signature / key identifying this system. PLEASE
Method action_ack_encode This message acknowledges an action. IMPORTANT: The acknowledgement
Method action_ack_send This message acknowledges an action. IMPORTANT: The acknowledgement
Method action_encode An action message allows to execute a certain onboard action. These
Method action_send An action message allows to execute a certain onboard action. These
Method set_mode_encode Set the system mode, as defined by enum MAV_MODE in
Method set_mode_send Set the system mode, as defined by enum MAV_MODE in
Method set_nav_mode_encode Set the system navigation mode, as defined by enum MAV_NAV_MODE in
Method set_nav_mode_send Set the system navigation mode, as defined by enum MAV_NAV_MODE in
Method param_request_read_encode Request to read the onboard parameter with the param_id string id.
Method param_request_read_send Request to read the onboard parameter with the param_id string id.
Method param_request_list_encode Request all parameters of this component. After his request, all
Method param_request_list_send Request all parameters of this component. After his request, all
Method param_value_encode Emit the value of a onboard parameter. The inclusion of param_count
Method param_value_send Emit the value of a onboard parameter. The inclusion of param_count
Method param_set_encode Set a parameter value TEMPORARILY to RAM. It will be reset to default
Method param_set_send Set a parameter value TEMPORARILY to RAM. It will be reset to default
Method gps_raw_int_encode The global position, as returned by the Global Positioning System
Method gps_raw_int_send The global position, as returned by the Global Positioning System
Method scaled_imu_encode The RAW IMU readings for the usual 9DOF sensor setup. This message
Method scaled_imu_send The RAW IMU readings for the usual 9DOF sensor setup. This message
Method gps_status_encode The positioning status, as reported by GPS. This message is intended
Method gps_status_send The positioning status, as reported by GPS. This message is intended
Method raw_imu_encode The RAW IMU readings for the usual 9DOF sensor setup. This message
Method raw_imu_send The RAW IMU readings for the usual 9DOF sensor setup. This message
Method raw_pressure_encode The RAW pressure readings for the typical setup of one absolute
Method raw_pressure_send The RAW pressure readings for the typical setup of one absolute
Method scaled_pressure_encode The pressure readings for the typical setup of one absolute and
Method scaled_pressure_send The pressure readings for the typical setup of one absolute and
Method attitude_encode The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Method attitude_send The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Method local_position_encode The filtered local position (e.g. fused computer vision and
Method local_position_send The filtered local position (e.g. fused computer vision and
Method global_position_encode The filtered global position (e.g. fused GPS and accelerometers).
Method global_position_send The filtered global position (e.g. fused GPS and accelerometers).
Method gps_raw_encode The global position, as returned by the Global Positioning System
Method gps_raw_send The global position, as returned by the Global Positioning System
Method sys_status_encode The general system state. If the system is following the MAVLink
Method sys_status_send The general system state. If the system is following the MAVLink
Method rc_channels_raw_encode The RAW values of the RC channels received. The standard PPM
Method rc_channels_raw_send The RAW values of the RC channels received. The standard PPM
Method rc_channels_scaled_encode The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
Method rc_channels_scaled_send The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
Method servo_output_raw_encode The RAW values of the servo outputs (for RC input from the remote, use
Method servo_output_raw_send The RAW values of the servo outputs (for RC input from the remote, use
Method waypoint_encode Message encoding a waypoint. This message is emitted to announce
Method waypoint_send Message encoding a waypoint. This message is emitted to announce
Method waypoint_request_encode Request the information of the waypoint with the sequence number seq.
Method waypoint_request_send Request the information of the waypoint with the sequence number seq.
Method waypoint_set_current_encode Set the waypoint with sequence number seq as current waypoint. This
Method waypoint_set_current_send Set the waypoint with sequence number seq as current waypoint. This
Method waypoint_current_encode Message that announces the sequence number of the current active
Method waypoint_current_send Message that announces the sequence number of the current active
Method waypoint_request_list_encode Request the overall list of waypoints from the system/component.
Method waypoint_request_list_send Request the overall list of waypoints from the system/component.
Method waypoint_count_encode This message is emitted as response to WAYPOINT_REQUEST_LIST by the
Method waypoint_count_send This message is emitted as response to WAYPOINT_REQUEST_LIST by the
Method waypoint_clear_all_encode Delete all waypoints at once.
Method waypoint_clear_all_send Delete all waypoints at once.
Method waypoint_reached_encode A certain waypoint has been reached. The system will either hold this
Method waypoint_reached_send A certain waypoint has been reached. The system will either hold this
Method waypoint_ack_encode Ack message during waypoint handling. The type field states if this
Method waypoint_ack_send Ack message during waypoint handling. The type field states if this
Method gps_set_global_origin_encode As local waypoints exist, the global waypoint reference allows to
Method gps_set_global_origin_send As local waypoints exist, the global waypoint reference allows to
Method gps_local_origin_set_encode Once the MAV sets a new GPS-Local correspondence, this message
Method gps_local_origin_set_send Once the MAV sets a new GPS-Local correspondence, this message
Method local_position_setpoint_set_encode Set the setpoint for a local position controller. This is the position
Method local_position_setpoint_set_send Set the setpoint for a local position controller. This is the position
Method local_position_setpoint_encode Transmit the current local setpoint of the controller to other MAVs
Method local_position_setpoint_send Transmit the current local setpoint of the controller to other MAVs
Method control_status_encode position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
Method control_status_send position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
Method safety_set_allowed_area_encode Set a safety zone (volume), which is defined by two corners of a cube.
Method safety_set_allowed_area_send Set a safety zone (volume), which is defined by two corners of a cube.
Method safety_allowed_area_encode Read out the safety zone the MAV currently assumes.
Method safety_allowed_area_send Read out the safety zone the MAV currently assumes.
Method set_roll_pitch_yaw_thrust_encode Set roll, pitch and yaw.
Method set_roll_pitch_yaw_thrust_send Set roll, pitch and yaw.
Method set_roll_pitch_yaw_speed_thrust_encode Set roll, pitch and yaw.
Method set_roll_pitch_yaw_speed_thrust_send Set roll, pitch and yaw.
Method roll_pitch_yaw_thrust_setpoint_encode Setpoint in roll, pitch, yaw currently active on the system.
Method roll_pitch_yaw_thrust_setpoint_send Setpoint in roll, pitch, yaw currently active on the system.
Method roll_pitch_yaw_speed_thrust_setpoint_encode Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
Method roll_pitch_yaw_speed_thrust_setpoint_send Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
Method nav_controller_output_encode Outputs of the APM navigation controller. The primary use of this
Method nav_controller_output_send Outputs of the APM navigation controller. The primary use of this
Method position_target_encode The goal position of the system. This position is the input to any
Method position_target_send The goal position of the system. This position is the input to any
Method state_correction_encode Corrects the systems state by adding an error correction term to the
Method state_correction_send Corrects the systems state by adding an error correction term to the
Method set_altitude_encode target : The system setting the altitude (uint8_t)
Method set_altitude_send target : The system setting the altitude (uint8_t)
Method request_data_stream_encode target_system : The target requested to send the message stream. (uint8_t)
Method request_data_stream_send target_system : The target requested to send the message stream. (uint8_t)
Method hil_state_encode This packet is useful for high throughput applications
Method hil_state_send This packet is useful for high throughput applications
Method hil_controls_encode Hardware in the loop control outputs
Method hil_controls_send Hardware in the loop control outputs
Method manual_control_encode target : The system to be controlled (uint8_t)
Method manual_control_send target : The system to be controlled (uint8_t)
Method rc_channels_override_encode The RAW values of the RC channels sent to the MAV to override info
Method rc_channels_override_send The RAW values of the RC channels sent to the MAV to override info
Method global_position_int_encode The filtered global position (e.g. fused GPS and accelerometers). The
Method global_position_int_send The filtered global position (e.g. fused GPS and accelerometers). The
Method vfr_hud_encode Metrics typically displayed on a HUD for fixed wing aircraft
Method vfr_hud_send Metrics typically displayed on a HUD for fixed wing aircraft
Method command_encode Send a command with up to four parameters to the MAV
Method command_send Send a command with up to four parameters to the MAV
Method command_ack_encode Report status of a command. Includes feedback wether the command was
Method command_ack_send Report status of a command. Includes feedback wether the command was
Method optical_flow_encode Optical flow from a flow sensor (e.g. optical mouse sensor)
Method optical_flow_send Optical flow from a flow sensor (e.g. optical mouse sensor)
Method debug_vect_encode name : Name (char)
Method debug_vect_send name : Name (char)
Method named_value_float_encode Send a key-value pair as float. The use of this message is discouraged
Method named_value_float_send Send a key-value pair as float. The use of this message is discouraged
Method named_value_int_encode Send a key-value pair as integer. The use of this message is
Method named_value_int_send Send a key-value pair as integer. The use of this message is
Method statustext_encode Status text message. These messages are printed in yellow in the COMM
Method statustext_send Status text message. These messages are printed in yellow in the COMM
Method debug_encode Send a debug value. The index is used to discriminate between values.
Method debug_send Send a debug value. The index is used to discriminate between values.
def __init__(self, file, srcSystem=0, srcComponent=0):
Undocumented
def set_callback(self, callback, *args, **kwargs):
Undocumented
def send(self, mavmsg):
send a MAVLink message
def bytes_needed(self):
return number of bytes needed for next parsing stage
def parse_char(self, c):
input some data bytes, possibly returning a new message
def decode(self, msgbuf):
decode a buffer as a MAVLink message
def heartbeat_encode(self, type, autopilot, mavlink_version):
The heartbeat message shows that a system is present and responding.
The type of the MAV and Autopilot hardware allow the receiving
system to treat further messages from this system appropriate (e.g.
by laying out the user interface based on the autopilot).

type                    : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
autopilot               : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t)
mavlink_version         : MAVLink version (uint8_t_mavlink_version)
def heartbeat_send(self, type, autopilot, mavlink_version):
The heartbeat message shows that a system is present and responding.
The type of the MAV and Autopilot hardware allow the receiving
system to treat further messages from this system appropriate (e.g.
by laying out the user interface based on the autopilot).

type                    : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t)
autopilot               : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t)
mavlink_version         : MAVLink version (uint8_t_mavlink_version)
def boot_encode(self, version):
The boot message indicates that a system is starting. The onboard
software version allows to keep track of onboard soft/firmware
revisions.

version                 : The onboard software version (uint32_t)
def boot_send(self, version):
The boot message indicates that a system is starting. The onboard
software version allows to keep track of onboard soft/firmware
revisions.

version                 : The onboard software version (uint32_t)
def system_time_encode(self, time_usec):
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.

time_usec               : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
def system_time_send(self, time_usec):
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.

time_usec               : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t)
def ping_encode(self, seq, target_system, target_component, time):
A ping message either requesting or responding to a ping. This allows
to measure the system latencies, including serial port, radio modem
and UDP connections.

seq                     : PING sequence (uint32_t)
target_system           : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
target_component        : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
time                    : Unix timestamp in microseconds (uint64_t)
def ping_send(self, seq, target_system, target_component, time):
A ping message either requesting or responding to a ping. This allows
to measure the system latencies, including serial port, radio modem
and UDP connections.

seq                     : PING sequence (uint32_t)
target_system           : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
target_component        : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t)
time                    : Unix timestamp in microseconds (uint64_t)
def system_time_utc_encode(self, utc_date, utc_time):
UTC date and time from GPS module

utc_date                : GPS UTC date ddmmyy (uint32_t)
utc_time                : GPS UTC time hhmmss (uint32_t)
def system_time_utc_send(self, utc_date, utc_time):
UTC date and time from GPS module

utc_date                : GPS UTC date ddmmyy (uint32_t)
utc_time                : GPS UTC time hhmmss (uint32_t)
def change_operator_control_encode(self, target_system, control_request, version, passkey):
Request to control this MAV

target_system           : System the GCS requests control for (uint8_t)
control_request         : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
version                 : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
passkey                 : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
def change_operator_control_send(self, target_system, control_request, version, passkey):
Request to control this MAV

target_system           : System the GCS requests control for (uint8_t)
control_request         : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
version                 : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t)
passkey                 : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char)
def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack):
Accept / deny control of this MAV

gcs_system_id           : ID of the GCS this message (uint8_t)
control_request         : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
ack                     : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
def change_operator_control_ack_send(self, gcs_system_id, control_request, ack):
Accept / deny control of this MAV

gcs_system_id           : ID of the GCS this message (uint8_t)
control_request         : 0: request control of this MAV, 1: Release control of this MAV (uint8_t)
ack                     : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t)
def auth_key_encode(self, key):
Emit an encrypted signature / key identifying this system. PLEASE
NOTE: This protocol has been kept simple, so transmitting the key
requires an encrypted channel for true safety.

key                     : key (char)
def auth_key_send(self, key):
Emit an encrypted signature / key identifying this system. PLEASE
NOTE: This protocol has been kept simple, so transmitting the key
requires an encrypted channel for true safety.

key                     : key (char)
def action_ack_encode(self, action, result):
This message acknowledges an action. IMPORTANT: The acknowledgement
can be also negative, e.g. the MAV rejects a reset message because
it is in-flight. The action ids are defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h

action                  : The action id (uint8_t)
result                  : 0: Action DENIED, 1: Action executed (uint8_t)
def action_ack_send(self, action, result):
This message acknowledges an action. IMPORTANT: The acknowledgement
can be also negative, e.g. the MAV rejects a reset message because
it is in-flight. The action ids are defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h

action                  : The action id (uint8_t)
result                  : 0: Action DENIED, 1: Action executed (uint8_t)
def action_encode(self, target, target_component, action):
An action message allows to execute a certain onboard action. These
include liftoff, land, storing parameters too EEPROM, shutddown,
etc. The action ids are defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h

target                  : The system executing the action (uint8_t)
target_component        : The component executing the action (uint8_t)
action                  : The action id (uint8_t)
def action_send(self, target, target_component, action):
An action message allows to execute a certain onboard action. These
include liftoff, land, storing parameters too EEPROM, shutddown,
etc. The action ids are defined in ENUM MAV_ACTION in
mavlink/include/mavlink_types.h

target                  : The system executing the action (uint8_t)
target_component        : The component executing the action (uint8_t)
action                  : The action id (uint8_t)
def set_mode_encode(self, target, mode):
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target component id as
the mode is by definition for the overall aircraft, not only for one
component.

target                  : The system setting the mode (uint8_t)
mode                    : The new mode (uint8_t)
def set_mode_send(self, target, mode):
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target component id as
the mode is by definition for the overall aircraft, not only for one
component.

target                  : The system setting the mode (uint8_t)
mode                    : The new mode (uint8_t)
def set_nav_mode_encode(self, target, nav_mode):
Set the system navigation mode, as defined by enum MAV_NAV_MODE in
mavlink/include/mavlink_types.h. The navigation mode applies to the
whole aircraft and thus all components.

target                  : The system setting the mode (uint8_t)
nav_mode                : The new navigation mode (uint8_t)
def set_nav_mode_send(self, target, nav_mode):
Set the system navigation mode, as defined by enum MAV_NAV_MODE in
mavlink/include/mavlink_types.h. The navigation mode applies to the
whole aircraft and thus all components.

target                  : The system setting the mode (uint8_t)
nav_mode                : The new navigation mode (uint8_t)
def param_request_read_encode(self, target_system, target_component, param_id, param_index):
Request to read the onboard parameter with the param_id string id.
Onboard parameters are stored as key[const char*] -> value[float].
This allows to send a parameter to any other component (such as the
GCS) without the need of previous knowledge of possible parameter
names. Thus the same GCS can store different parameters for
different autopilots. See also
http://qgroundcontrol.org/parameter_interface for a full
documentation of QGroundControl and IMU code.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
param_id                : Onboard parameter id (uint8_t)
param_index             : Parameter index. Send -1 to use the param ID field as identifier (int16_t)
def param_request_read_send(self, target_system, target_component, param_id, param_index):
Request to read the onboard parameter with the param_id string id.
Onboard parameters are stored as key[const char*] -> value[float].
This allows to send a parameter to any other component (such as the
GCS) without the need of previous knowledge of possible parameter
names. Thus the same GCS can store different parameters for
different autopilots. See also
http://qgroundcontrol.org/parameter_interface for a full
documentation of QGroundControl and IMU code.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
param_id                : Onboard parameter id (uint8_t)
param_index             : Parameter index. Send -1 to use the param ID field as identifier (int16_t)
def param_request_list_encode(self, target_system, target_component):
Request all parameters of this component. After his request, all
parameters are emitted.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def param_request_list_send(self, target_system, target_component):
Request all parameters of this component. After his request, all
parameters are emitted.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def param_value_encode(self, param_id, param_value, param_count, param_index):
Emit the value of a onboard parameter. The inclusion of param_count
and param_index in the message allows the recipient to keep track of
received parameters and allows him to re-request missing parameters
after a loss or timeout.

param_id                : Onboard parameter id (uint8_t)
param_value             : Onboard parameter value (float)
param_count             : Total number of onboard parameters (uint16_t)
param_index             : Index of this onboard parameter (uint16_t)
def param_value_send(self, param_id, param_value, param_count, param_index):
Emit the value of a onboard parameter. The inclusion of param_count
and param_index in the message allows the recipient to keep track of
received parameters and allows him to re-request missing parameters
after a loss or timeout.

param_id                : Onboard parameter id (uint8_t)
param_value             : Onboard parameter value (float)
param_count             : Total number of onboard parameters (uint16_t)
param_index             : Index of this onboard parameter (uint16_t)
def param_set_encode(self, target_system, target_component, param_id, param_value):
Set a parameter value TEMPORARILY to RAM. It will be reset to default
on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to
PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The
receiving component should acknowledge the new parameter value by
sending a param_value message to all communication partners. This
will also ensure that multiple GCS all have an up-to-date list of
all parameters. If the sending GCS did not receive a PARAM_VALUE
message within its timeout time, it should re-send the PARAM_SET
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
param_id                : Onboard parameter id (uint8_t)
param_value             : Onboard parameter value (float)
def param_set_send(self, target_system, target_component, param_id, param_value):
Set a parameter value TEMPORARILY to RAM. It will be reset to default
on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to
PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The
receiving component should acknowledge the new parameter value by
sending a param_value message to all communication partners. This
will also ensure that multiple GCS all have an up-to-date list of
all parameters. If the sending GCS did not receive a PARAM_VALUE
message within its timeout time, it should re-send the PARAM_SET
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
param_id                : Onboard parameter id (uint8_t)
param_value             : Onboard parameter value (float)
def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the sytem, but
rather a RAW sensor value. See message GLOBAL_POSITION for the
global position estimate. Coordinate frame is right-handed, Z-axis
up (GPS frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type                : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat                     : Latitude in 1E7 degrees (int32_t)
lon                     : Longitude in 1E7 degrees (int32_t)
alt                     : Altitude in 1E3 meters (millimeters) (int32_t)
eph                     : GPS HDOP (float)
epv                     : GPS VDOP (float)
v                       : GPS ground speed (m/s) (float)
hdg                     : Compass heading in degrees, 0..360 degrees (float)
def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the sytem, but
rather a RAW sensor value. See message GLOBAL_POSITION for the
global position estimate. Coordinate frame is right-handed, Z-axis
up (GPS frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type                : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat                     : Latitude in 1E7 degrees (int32_t)
lon                     : Longitude in 1E7 degrees (int32_t)
alt                     : Altitude in 1E3 meters (millimeters) (int32_t)
eph                     : GPS HDOP (float)
epv                     : GPS VDOP (float)
v                       : GPS ground speed (m/s) (float)
hdg                     : Compass heading in degrees, 0..360 degrees (float)
def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
The RAW IMU readings for the usual 9DOF sensor setup. This message
should contain the scaled values to the described units

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc                    : X acceleration (mg) (int16_t)
yacc                    : Y acceleration (mg) (int16_t)
zacc                    : Z acceleration (mg) (int16_t)
xgyro                   : Angular speed around X axis (millirad /sec) (int16_t)
ygyro                   : Angular speed around Y axis (millirad /sec) (int16_t)
zgyro                   : Angular speed around Z axis (millirad /sec) (int16_t)
xmag                    : X Magnetic field (milli tesla) (int16_t)
ymag                    : Y Magnetic field (milli tesla) (int16_t)
zmag                    : Z Magnetic field (milli tesla) (int16_t)
def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
The RAW IMU readings for the usual 9DOF sensor setup. This message
should contain the scaled values to the described units

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc                    : X acceleration (mg) (int16_t)
yacc                    : Y acceleration (mg) (int16_t)
zacc                    : Z acceleration (mg) (int16_t)
xgyro                   : Angular speed around X axis (millirad /sec) (int16_t)
ygyro                   : Angular speed around Y axis (millirad /sec) (int16_t)
zgyro                   : Angular speed around Z axis (millirad /sec) (int16_t)
xmag                    : X Magnetic field (milli tesla) (int16_t)
ymag                    : Y Magnetic field (milli tesla) (int16_t)
zmag                    : Z Magnetic field (milli tesla) (int16_t)
def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
The positioning status, as reported by GPS. This message is intended
to display status information about each satellite visible to the
receiver. See message GLOBAL_POSITION for the global position
estimate. This message can contain information for up to 20
satellites.

satellites_visible      : Number of satellites visible (uint8_t)
satellite_prn           : Global satellite ID (uint8_t)
satellite_used          : 0: Satellite not used, 1: used for localization (uint8_t)
satellite_elevation     : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
satellite_azimuth       : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
satellite_snr           : Signal to noise ratio of satellite (uint8_t)
def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
The positioning status, as reported by GPS. This message is intended
to display status information about each satellite visible to the
receiver. See message GLOBAL_POSITION for the global position
estimate. This message can contain information for up to 20
satellites.

satellites_visible      : Number of satellites visible (uint8_t)
satellite_prn           : Global satellite ID (uint8_t)
satellite_used          : 0: Satellite not used, 1: used for localization (uint8_t)
satellite_elevation     : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t)
satellite_azimuth       : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t)
satellite_snr           : Signal to noise ratio of satellite (uint8_t)
def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
The RAW IMU readings for the usual 9DOF sensor setup. This message
should always contain the true raw values without any scaling to
allow data capture and system debugging.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc                    : X acceleration (raw) (int16_t)
yacc                    : Y acceleration (raw) (int16_t)
zacc                    : Z acceleration (raw) (int16_t)
xgyro                   : Angular speed around X axis (raw) (int16_t)
ygyro                   : Angular speed around Y axis (raw) (int16_t)
zgyro                   : Angular speed around Z axis (raw) (int16_t)
xmag                    : X Magnetic field (raw) (int16_t)
ymag                    : Y Magnetic field (raw) (int16_t)
zmag                    : Z Magnetic field (raw) (int16_t)
def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
The RAW IMU readings for the usual 9DOF sensor setup. This message
should always contain the true raw values without any scaling to
allow data capture and system debugging.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
xacc                    : X acceleration (raw) (int16_t)
yacc                    : Y acceleration (raw) (int16_t)
zacc                    : Z acceleration (raw) (int16_t)
xgyro                   : Angular speed around X axis (raw) (int16_t)
ygyro                   : Angular speed around Y axis (raw) (int16_t)
zgyro                   : Angular speed around Z axis (raw) (int16_t)
xmag                    : X Magnetic field (raw) (int16_t)
ymag                    : Y Magnetic field (raw) (int16_t)
zmag                    : Z Magnetic field (raw) (int16_t)
def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature):
The RAW pressure readings for the typical setup of one absolute
pressure and one differential pressure sensor. The sensor values
should be the raw, UNSCALED ADC values.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs               : Absolute pressure (raw) (int16_t)
press_diff1             : Differential pressure 1 (raw) (int16_t)
press_diff2             : Differential pressure 2 (raw) (int16_t)
temperature             : Raw Temperature measurement (raw) (int16_t)
def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature):
The RAW pressure readings for the typical setup of one absolute
pressure and one differential pressure sensor. The sensor values
should be the raw, UNSCALED ADC values.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs               : Absolute pressure (raw) (int16_t)
press_diff1             : Differential pressure 1 (raw) (int16_t)
press_diff2             : Differential pressure 2 (raw) (int16_t)
temperature             : Raw Temperature measurement (raw) (int16_t)
def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature):
The pressure readings for the typical setup of one absolute and
differential pressure sensor. The units are as specified in each
field.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs               : Absolute pressure (hectopascal) (float)
press_diff              : Differential pressure 1 (hectopascal) (float)
temperature             : Temperature measurement (0.01 degrees celsius) (int16_t)
def scaled_pressure_send(self, usec, press_abs, press_diff, temperature):
The pressure readings for the typical setup of one absolute and
differential pressure sensor. The units are as specified in each
field.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
press_abs               : Absolute pressure (hectopascal) (float)
press_diff              : Differential pressure 1 (hectopascal) (float)
temperature             : Temperature measurement (0.01 degrees celsius) (int16_t)
def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Y-right).

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll                    : Roll angle (rad) (float)
pitch                   : Pitch angle (rad) (float)
yaw                     : Yaw angle (rad) (float)
rollspeed               : Roll angular speed (rad/s) (float)
pitchspeed              : Pitch angular speed (rad/s) (float)
yawspeed                : Yaw angular speed (rad/s) (float)
def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
The attitude in the aeronautical frame (right-handed, Z-down, X-front,
Y-right).

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll                    : Roll angle (rad) (float)
pitch                   : Pitch angle (rad) (float)
yaw                     : Yaw angle (rad) (float)
rollspeed               : Roll angular speed (rad/s) (float)
pitchspeed              : Pitch angular speed (rad/s) (float)
yawspeed                : Yaw angular speed (rad/s) (float)
def local_position_encode(self, usec, x, y, z, vx, vy, vz):
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed, Z-axis down
(aeronautical frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
x                       : X Position (float)
y                       : Y Position (float)
z                       : Z Position (float)
vx                      : X Speed (float)
vy                      : Y Speed (float)
vz                      : Z Speed (float)
def local_position_send(self, usec, x, y, z, vx, vy, vz):
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed, Z-axis down
(aeronautical frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
x                       : X Position (float)
y                       : Y Position (float)
z                       : Z Position (float)
vx                      : X Speed (float)
vy                      : Y Speed (float)
vz                      : Z Speed (float)
def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz):
The filtered global position (e.g. fused GPS and accelerometers).
Coordinate frame is right-handed, Z-axis up (GPS frame)

usec                    : Timestamp (microseconds since unix epoch) (uint64_t)
lat                     : Latitude, in degrees (float)
lon                     : Longitude, in degrees (float)
alt                     : Absolute altitude, in meters (float)
vx                      : X Speed (in Latitude direction, positive: going north) (float)
vy                      : Y Speed (in Longitude direction, positive: going east) (float)
vz                      : Z Speed (in Altitude direction, positive: going up) (float)
def global_position_send(self, usec, lat, lon, alt, vx, vy, vz):
The filtered global position (e.g. fused GPS and accelerometers).
Coordinate frame is right-handed, Z-axis up (GPS frame)

usec                    : Timestamp (microseconds since unix epoch) (uint64_t)
lat                     : Latitude, in degrees (float)
lon                     : Longitude, in degrees (float)
alt                     : Absolute altitude, in meters (float)
vx                      : X Speed (in Latitude direction, positive: going north) (float)
vy                      : Y Speed (in Longitude direction, positive: going east) (float)
vz                      : Z Speed (in Altitude direction, positive: going up) (float)
def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the sytem, but
rather a RAW sensor value. See message GLOBAL_POSITION for the
global position estimate. Coordinate frame is right-handed, Z-axis
up (GPS frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type                : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat                     : Latitude in degrees (float)
lon                     : Longitude in degrees (float)
alt                     : Altitude in meters (float)
eph                     : GPS HDOP (float)
epv                     : GPS VDOP (float)
v                       : GPS ground speed (float)
hdg                     : Compass heading in degrees, 0..360 degrees (float)
def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position estimate of the sytem, but
rather a RAW sensor value. See message GLOBAL_POSITION for the
global position estimate. Coordinate frame is right-handed, Z-axis
up (GPS frame)

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
fix_type                : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t)
lat                     : Latitude in degrees (float)
lon                     : Longitude in degrees (float)
alt                     : Altitude in meters (float)
eph                     : GPS HDOP (float)
epv                     : GPS VDOP (float)
v                       : GPS ground speed (float)
hdg                     : Compass heading in degrees, 0..360 degrees (float)
def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
The general system state. If the system is following the MAVLink
standard, the system state is mainly defined by three orthogonal
states/modes: The system mode, which is either LOCKED (motors shut
down and locked), MANUAL (system under RC control), GUIDED (system
with autonomous position control, position setpoint controlled
manually) or AUTO (system guided by path/waypoint planner). The
NAV_MODE defined the current flight state: LIFTOFF (often an open-
loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the
internal navigation state machine. The system status shows wether
the system is currently active or not and if an emergency occured.
During the CRITICAL and EMERGENCY states the MAV is still considered
to be active, but should start emergency procedures autonomously.
After a failure occured it should first move from active to critical
to allow manual intervention and then move to emergency after a
certain timeout.

mode                    : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t)
nav_mode                : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t)
status                  : System status flag, see MAV_STATUS ENUM (uint8_t)
load                    : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
vbat                    : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
battery_remaining       : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t)
packet_drop             : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t)
def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
The general system state. If the system is following the MAVLink
standard, the system state is mainly defined by three orthogonal
states/modes: The system mode, which is either LOCKED (motors shut
down and locked), MANUAL (system under RC control), GUIDED (system
with autonomous position control, position setpoint controlled
manually) or AUTO (system guided by path/waypoint planner). The
NAV_MODE defined the current flight state: LIFTOFF (often an open-
loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the
internal navigation state machine. The system status shows wether
the system is currently active or not and if an emergency occured.
During the CRITICAL and EMERGENCY states the MAV is still considered
to be active, but should start emergency procedures autonomously.
After a failure occured it should first move from active to critical
to allow manual intervention and then move to emergency after a
certain timeout.

mode                    : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t)
nav_mode                : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t)
status                  : System status flag, see MAV_STATUS ENUM (uint8_t)
load                    : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t)
vbat                    : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t)
battery_remaining       : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t)
packet_drop             : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t)
def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000 microseconds:
100%. Individual receivers/transmitters might violate this
specification.

chan1_raw               : RC channel 1 value, in microseconds (uint16_t)
chan2_raw               : RC channel 2 value, in microseconds (uint16_t)
chan3_raw               : RC channel 3 value, in microseconds (uint16_t)
chan4_raw               : RC channel 4 value, in microseconds (uint16_t)
chan5_raw               : RC channel 5 value, in microseconds (uint16_t)
chan6_raw               : RC channel 6 value, in microseconds (uint16_t)
chan7_raw               : RC channel 7 value, in microseconds (uint16_t)
chan8_raw               : RC channel 8 value, in microseconds (uint16_t)
rssi                    : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000 microseconds:
100%. Individual receivers/transmitters might violate this
specification.

chan1_raw               : RC channel 1 value, in microseconds (uint16_t)
chan2_raw               : RC channel 2 value, in microseconds (uint16_t)
chan3_raw               : RC channel 3 value, in microseconds (uint16_t)
chan4_raw               : RC channel 4 value, in microseconds (uint16_t)
chan5_raw               : RC channel 5 value, in microseconds (uint16_t)
chan6_raw               : RC channel 6 value, in microseconds (uint16_t)
chan7_raw               : RC channel 7 value, in microseconds (uint16_t)
chan8_raw               : RC channel 8 value, in microseconds (uint16_t)
rssi                    : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
(100%) 10000

chan1_scaled            : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan2_scaled            : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan3_scaled            : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan4_scaled            : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan5_scaled            : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan6_scaled            : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan7_scaled            : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan8_scaled            : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
rssi                    : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi):
The scaled values of the RC channels received. (-100%) -10000, (0%) 0,
(100%) 10000

chan1_scaled            : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan2_scaled            : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan3_scaled            : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan4_scaled            : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan5_scaled            : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan6_scaled            : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan7_scaled            : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
chan8_scaled            : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t)
rssi                    : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t)
def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
The RAW values of the servo outputs (for RC input from the remote, use
the RC_CHANNELS messages). The standard PPM modulation is as
follows: 1000 microseconds: 0%, 2000 microseconds: 100%.

servo1_raw              : Servo output 1 value, in microseconds (uint16_t)
servo2_raw              : Servo output 2 value, in microseconds (uint16_t)
servo3_raw              : Servo output 3 value, in microseconds (uint16_t)
servo4_raw              : Servo output 4 value, in microseconds (uint16_t)
servo5_raw              : Servo output 5 value, in microseconds (uint16_t)
servo6_raw              : Servo output 6 value, in microseconds (uint16_t)
servo7_raw              : Servo output 7 value, in microseconds (uint16_t)
servo8_raw              : Servo output 8 value, in microseconds (uint16_t)
def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw):
The RAW values of the servo outputs (for RC input from the remote, use
the RC_CHANNELS messages). The standard PPM modulation is as
follows: 1000 microseconds: 0%, 2000 microseconds: 100%.

servo1_raw              : Servo output 1 value, in microseconds (uint16_t)
servo2_raw              : Servo output 2 value, in microseconds (uint16_t)
servo3_raw              : Servo output 3 value, in microseconds (uint16_t)
servo4_raw              : Servo output 4 value, in microseconds (uint16_t)
servo5_raw              : Servo output 5 value, in microseconds (uint16_t)
servo6_raw              : Servo output 6 value, in microseconds (uint16_t)
servo7_raw              : Servo output 7 value, in microseconds (uint16_t)
servo8_raw              : Servo output 8 value, in microseconds (uint16_t)
def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on the system. The
waypoint can be either in x, y, z meters (type: LOCAL) or x:lat,
y:lon, z:altitude. Local frame is Z-down, right handed, global frame
is Z-up, right handed

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
frame                   : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t)
command                 : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t)
current                 : false:0, true:1 (uint8_t)
autocontinue            : autocontinue to next wp (uint8_t)
param1                  : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float)
param2                  : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
param3                  : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float)
param4                  : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float)
x                       : PARAM5 / local: x position, global: latitude (float)
y                       : PARAM6 / y position: global: longitude (float)
z                       : PARAM7 / z position: global: altitude (float)
def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z):
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on the system. The
waypoint can be either in x, y, z meters (type: LOCAL) or x:lat,
y:lon, z:altitude. Local frame is Z-down, right handed, global frame
is Z-up, right handed

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
frame                   : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t)
command                 : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t)
current                 : false:0, true:1 (uint8_t)
autocontinue            : autocontinue to next wp (uint8_t)
param1                  : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float)
param2                  : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float)
param3                  : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float)
param4                  : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float)
x                       : PARAM5 / local: x position, global: latitude (float)
y                       : PARAM6 / y position: global: longitude (float)
z                       : PARAM7 / z position: global: altitude (float)
def waypoint_request_encode(self, target_system, target_component, seq):
Request the information of the waypoint with the sequence number seq.
The response of the system to this message should be a WAYPOINT
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
def waypoint_request_send(self, target_system, target_component, seq):
Request the information of the waypoint with the sequence number seq.
The response of the system to this message should be a WAYPOINT
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
def waypoint_set_current_encode(self, target_system, target_component, seq):
Set the waypoint with sequence number seq as current waypoint. This
means that the MAV will continue to this waypoint on the shortest
path (not following the waypoints in-between).

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
def waypoint_set_current_send(self, target_system, target_component, seq):
Set the waypoint with sequence number seq as current waypoint. This
means that the MAV will continue to this waypoint on the shortest
path (not following the waypoints in-between).

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
seq                     : Sequence (uint16_t)
def waypoint_current_encode(self, seq):
Message that announces the sequence number of the current active
waypoint. The MAV will fly towards this waypoint.

seq                     : Sequence (uint16_t)
def waypoint_current_send(self, seq):
Message that announces the sequence number of the current active
waypoint. The MAV will fly towards this waypoint.

seq                     : Sequence (uint16_t)
def waypoint_request_list_encode(self, target_system, target_component):
Request the overall list of waypoints from the system/component.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def waypoint_request_list_send(self, target_system, target_component):
Request the overall list of waypoints from the system/component.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def waypoint_count_encode(self, target_system, target_component, count):
This message is emitted as response to WAYPOINT_REQUEST_LIST by the
MAV. The GCS can then request the individual waypoints based on the
knowledge of the total number of waypoints.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
count                   : Number of Waypoints in the Sequence (uint16_t)
def waypoint_count_send(self, target_system, target_component, count):
This message is emitted as response to WAYPOINT_REQUEST_LIST by the
MAV. The GCS can then request the individual waypoints based on the
knowledge of the total number of waypoints.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
count                   : Number of Waypoints in the Sequence (uint16_t)
def waypoint_clear_all_encode(self, target_system, target_component):
Delete all waypoints at once.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def waypoint_clear_all_send(self, target_system, target_component):
Delete all waypoints at once.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
def waypoint_reached_encode(self, seq):
A certain waypoint has been reached. The system will either hold this
position (or circle on the orbit) or (if the autocontinue on the WP
was set) continue to the next waypoint.

seq                     : Sequence (uint16_t)
def waypoint_reached_send(self, seq):
A certain waypoint has been reached. The system will either hold this
position (or circle on the orbit) or (if the autocontinue on the WP
was set) continue to the next waypoint.

seq                     : Sequence (uint16_t)
def waypoint_ack_encode(self, target_system, target_component, type):
Ack message during waypoint handling. The type field states if this
message is a positive ack (type=0) or if an error happened (type
=non-zero).

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
type                    : 0: OK, 1: Error (uint8_t)
def waypoint_ack_send(self, target_system, target_component, type):
Ack message during waypoint handling. The type field states if this
message is a positive ack (type=0) or if an error happened (type
=non-zero).

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
type                    : 0: OK, 1: Error (uint8_t)
def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude):
As local waypoints exist, the global waypoint reference allows to
transform between the local coordinate frame and the global (GPS)
coordinate frame. This can be necessary when e.g. in- and outdoor
settings are connected and the MAV should move from in- to outdoor.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
latitude                : global position * 1E7 (int32_t)
longitude               : global position * 1E7 (int32_t)
altitude                : global position * 1000 (int32_t)
def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude):
As local waypoints exist, the global waypoint reference allows to
transform between the local coordinate frame and the global (GPS)
coordinate frame. This can be necessary when e.g. in- and outdoor
settings are connected and the MAV should move from in- to outdoor.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
latitude                : global position * 1E7 (int32_t)
longitude               : global position * 1E7 (int32_t)
altitude                : global position * 1000 (int32_t)
def gps_local_origin_set_encode(self, latitude, longitude, altitude):
Once the MAV sets a new GPS-Local correspondence, this message
announces the origin (0,0,0) position

latitude                : Latitude (WGS84), expressed as * 1E7 (int32_t)
longitude               : Longitude (WGS84), expressed as * 1E7 (int32_t)
altitude                : Altitude(WGS84), expressed as * 1000 (int32_t)
def gps_local_origin_set_send(self, latitude, longitude, altitude):
Once the MAV sets a new GPS-Local correspondence, this message
announces the origin (0,0,0) position

latitude                : Latitude (WGS84), expressed as * 1E7 (int32_t)
longitude               : Longitude (WGS84), expressed as * 1E7 (int32_t)
altitude                : Altitude(WGS84), expressed as * 1000 (int32_t)
def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw):
Set the setpoint for a local position controller. This is the position
in local coordinates the MAV should fly to. This message is sent by
the path/waypoint planner to the onboard position controller. As
some MAVs have a degree of freedom in yaw (e.g. all
helicopters/quadrotors), the desired yaw angle is part of the
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : Desired yaw angle (float)
def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw):
Set the setpoint for a local position controller. This is the position
in local coordinates the MAV should fly to. This message is sent by
the path/waypoint planner to the onboard position controller. As
some MAVs have a degree of freedom in yaw (e.g. all
helicopters/quadrotors), the desired yaw angle is part of the
message.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : Desired yaw angle (float)
def local_position_setpoint_encode(self, x, y, z, yaw):
Transmit the current local setpoint of the controller to other MAVs
(collision avoidance) and to the GCS.

x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : Desired yaw angle (float)
def local_position_setpoint_send(self, x, y, z, yaw):
Transmit the current local setpoint of the controller to other MAVs
(collision avoidance) and to the GCS.

x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : Desired yaw angle (float)
def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw):
position_fix            : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
vision_fix              : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t)
gps_fix                 : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t)
ahrs_health             : Attitude estimation health: 0: poor, 255: excellent (uint8_t)
control_att             : 0: Attitude control disabled, 1: enabled (uint8_t)
control_pos_xy          : 0: X, Y position control disabled, 1: enabled (uint8_t)
control_pos_z           : 0: Z position control disabled, 1: enabled (uint8_t)
control_pos_yaw         : 0: Yaw angle control disabled, 1: enabled (uint8_t)
def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw):
position_fix            : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t)
vision_fix              : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t)
gps_fix                 : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t)
ahrs_health             : Attitude estimation health: 0: poor, 255: excellent (uint8_t)
control_att             : 0: Attitude control disabled, 1: enabled (uint8_t)
control_pos_xy          : 0: X, Y position control disabled, 1: enabled (uint8_t)
control_pos_z           : 0: Z position control disabled, 1: enabled (uint8_t)
control_pos_yaw         : 0: Yaw angle control disabled, 1: enabled (uint8_t)
def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
Set a safety zone (volume), which is defined by two corners of a cube.
This message can be used to tell the MAV which setpoints/waypoints
to accept and which to reject. Safety areas are often enforced by
national or competition regulations.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
frame                   : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x                     : x position 1 / Latitude 1 (float)
p1y                     : y position 1 / Longitude 1 (float)
p1z                     : z position 1 / Altitude 1 (float)
p2x                     : x position 2 / Latitude 2 (float)
p2y                     : y position 2 / Longitude 2 (float)
p2z                     : z position 2 / Altitude 2 (float)
def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z):
Set a safety zone (volume), which is defined by two corners of a cube.
This message can be used to tell the MAV which setpoints/waypoints
to accept and which to reject. Safety areas are often enforced by
national or competition regulations.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
frame                   : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x                     : x position 1 / Latitude 1 (float)
p1y                     : y position 1 / Longitude 1 (float)
p1z                     : z position 1 / Altitude 1 (float)
p2x                     : x position 2 / Latitude 2 (float)
p2y                     : y position 2 / Longitude 2 (float)
p2z                     : z position 2 / Altitude 2 (float)
def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
Read out the safety zone the MAV currently assumes.

frame                   : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x                     : x position 1 / Latitude 1 (float)
p1y                     : y position 1 / Longitude 1 (float)
p1z                     : z position 1 / Altitude 1 (float)
p2x                     : x position 2 / Latitude 2 (float)
p2y                     : y position 2 / Longitude 2 (float)
p2z                     : z position 2 / Altitude 2 (float)
def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z):
Read out the safety zone the MAV currently assumes.

frame                   : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t)
p1x                     : x position 1 / Latitude 1 (float)
p1y                     : y position 1 / Longitude 1 (float)
p1z                     : z position 1 / Altitude 1 (float)
p2x                     : x position 2 / Latitude 2 (float)
p2y                     : y position 2 / Longitude 2 (float)
p2z                     : z position 2 / Altitude 2 (float)
def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust):
Set roll, pitch and yaw.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
roll                    : Desired roll angle in radians (float)
pitch                   : Desired pitch angle in radians (float)
yaw                     : Desired yaw angle in radians (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust):
Set roll, pitch and yaw.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
roll                    : Desired roll angle in radians (float)
pitch                   : Desired pitch angle in radians (float)
yaw                     : Desired yaw angle in radians (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
Set roll, pitch and yaw.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
roll_speed              : Desired roll angular speed in rad/s (float)
pitch_speed             : Desired pitch angular speed in rad/s (float)
yaw_speed               : Desired yaw angular speed in rad/s (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust):
Set roll, pitch and yaw.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
roll_speed              : Desired roll angular speed in rad/s (float)
pitch_speed             : Desired pitch angular speed in rad/s (float)
yaw_speed               : Desired yaw angular speed in rad/s (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust):
Setpoint in roll, pitch, yaw currently active on the system.

time_us                 : Timestamp in micro seconds since unix epoch (uint64_t)
roll                    : Desired roll angle in radians (float)
pitch                   : Desired pitch angle in radians (float)
yaw                     : Desired yaw angle in radians (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust):
Setpoint in roll, pitch, yaw currently active on the system.

time_us                 : Timestamp in micro seconds since unix epoch (uint64_t)
roll                    : Desired roll angle in radians (float)
pitch                   : Desired pitch angle in radians (float)
yaw                     : Desired yaw angle in radians (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust):
Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
system.

time_us                 : Timestamp in micro seconds since unix epoch (uint64_t)
roll_speed              : Desired roll angular speed in rad/s (float)
pitch_speed             : Desired pitch angular speed in rad/s (float)
yaw_speed               : Desired yaw angular speed in rad/s (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust):
Setpoint in rollspeed, pitchspeed, yawspeed currently active on the
system.

time_us                 : Timestamp in micro seconds since unix epoch (uint64_t)
roll_speed              : Desired roll angular speed in rad/s (float)
pitch_speed             : Desired pitch angular speed in rad/s (float)
yaw_speed               : Desired yaw angular speed in rad/s (float)
thrust                  : Collective thrust, normalized to 0 .. 1 (float)
def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
Outputs of the APM navigation controller. The primary use of this
message is to check the response and signs of the controller before
actual flight and to assist with tuning controller parameters

nav_roll                : Current desired roll in degrees (float)
nav_pitch               : Current desired pitch in degrees (float)
nav_bearing             : Current desired heading in degrees (int16_t)
target_bearing          : Bearing to current waypoint/target in degrees (int16_t)
wp_dist                 : Distance to active waypoint in meters (uint16_t)
alt_error               : Current altitude error in meters (float)
aspd_error              : Current airspeed error in meters/second (float)
xtrack_error            : Current crosstrack error on x-y plane in meters (float)
def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error):
Outputs of the APM navigation controller. The primary use of this
message is to check the response and signs of the controller before
actual flight and to assist with tuning controller parameters

nav_roll                : Current desired roll in degrees (float)
nav_pitch               : Current desired pitch in degrees (float)
nav_bearing             : Current desired heading in degrees (int16_t)
target_bearing          : Bearing to current waypoint/target in degrees (int16_t)
wp_dist                 : Distance to active waypoint in meters (uint16_t)
alt_error               : Current altitude error in meters (float)
aspd_error              : Current airspeed error in meters/second (float)
xtrack_error            : Current crosstrack error on x-y plane in meters (float)
def position_target_encode(self, x, y, z, yaw):
The goal position of the system. This position is the input to any
navigation or path planning algorithm and does NOT represent the
current controller setpoint.

x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : yaw orientation in radians, 0 = NORTH (float)
def position_target_send(self, x, y, z, yaw):
The goal position of the system. This position is the input to any
navigation or path planning algorithm and does NOT represent the
current controller setpoint.

x                       : x position (float)
y                       : y position (float)
z                       : z position (float)
yaw                     : yaw orientation in radians, 0 = NORTH (float)
def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
Corrects the systems state by adding an error correction term to the
position and velocity, and by rotating the attitude by a correction
angle.

xErr                    : x position error (float)
yErr                    : y position error (float)
zErr                    : z position error (float)
rollErr                 : roll error (radians) (float)
pitchErr                : pitch error (radians) (float)
yawErr                  : yaw error (radians) (float)
vxErr                   : x velocity (float)
vyErr                   : y velocity (float)
vzErr                   : z velocity (float)
def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr):
Corrects the systems state by adding an error correction term to the
position and velocity, and by rotating the attitude by a correction
angle.

xErr                    : x position error (float)
yErr                    : y position error (float)
zErr                    : z position error (float)
rollErr                 : roll error (radians) (float)
pitchErr                : pitch error (radians) (float)
yawErr                  : yaw error (radians) (float)
vxErr                   : x velocity (float)
vyErr                   : y velocity (float)
vzErr                   : z velocity (float)
def set_altitude_encode(self, target, mode):
target                  : The system setting the altitude (uint8_t)
mode                    : The new altitude in meters (uint32_t)
def set_altitude_send(self, target, mode):
target                  : The system setting the altitude (uint8_t)
mode                    : The new altitude in meters (uint32_t)
def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
target_system           : The target requested to send the message stream. (uint8_t)
target_component        : The target requested to send the message stream. (uint8_t)
req_stream_id           : The ID of the requested message type (uint8_t)
req_message_rate        : Update rate in Hertz (uint16_t)
start_stop              : 1 to start sending, 0 to stop sending. (uint8_t)
def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop):
target_system           : The target requested to send the message stream. (uint8_t)
target_component        : The target requested to send the message stream. (uint8_t)
req_stream_id           : The ID of the requested message type (uint8_t)
req_message_rate        : Update rate in Hertz (uint16_t)
start_stop              : 1 to start sending, 0 to stop sending. (uint8_t)
def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
This packet is useful for high throughput                 applications
such as hardware in the loop simulations.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll                    : Roll angle (rad) (float)
pitch                   : Pitch angle (rad) (float)
yaw                     : Yaw angle (rad) (float)
rollspeed               : Roll angular speed (rad/s) (float)
pitchspeed              : Pitch angular speed (rad/s) (float)
yawspeed                : Yaw angular speed (rad/s) (float)
lat                     : Latitude, expressed as * 1E7 (int32_t)
lon                     : Longitude, expressed as * 1E7 (int32_t)
alt                     : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx                      : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy                      : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz                      : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
xacc                    : X acceleration (mg) (int16_t)
yacc                    : Y acceleration (mg) (int16_t)
zacc                    : Z acceleration (mg) (int16_t)
def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc):
This packet is useful for high throughput                 applications
such as hardware in the loop simulations.

usec                    : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll                    : Roll angle (rad) (float)
pitch                   : Pitch angle (rad) (float)
yaw                     : Yaw angle (rad) (float)
rollspeed               : Roll angular speed (rad/s) (float)
pitchspeed              : Pitch angular speed (rad/s) (float)
yawspeed                : Yaw angular speed (rad/s) (float)
lat                     : Latitude, expressed as * 1E7 (int32_t)
lon                     : Longitude, expressed as * 1E7 (int32_t)
alt                     : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx                      : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy                      : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz                      : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
xacc                    : X acceleration (mg) (int16_t)
yacc                    : Y acceleration (mg) (int16_t)
zacc                    : Z acceleration (mg) (int16_t)
def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode):
Hardware in the loop control outputs

time_us                 : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll_ailerons           : Control output -3 .. 1 (float)
pitch_elevator          : Control output -1 .. 1 (float)
yaw_rudder              : Control output -1 .. 1 (float)
throttle                : Throttle 0 .. 1 (float)
mode                    : System mode (MAV_MODE) (uint8_t)
nav_mode                : Navigation mode (MAV_NAV_MODE) (uint8_t)
def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode):
Hardware in the loop control outputs

time_us                 : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t)
roll_ailerons           : Control output -3 .. 1 (float)
pitch_elevator          : Control output -1 .. 1 (float)
yaw_rudder              : Control output -1 .. 1 (float)
throttle                : Throttle 0 .. 1 (float)
mode                    : System mode (MAV_MODE) (uint8_t)
nav_mode                : Navigation mode (MAV_NAV_MODE) (uint8_t)
def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual):
target                  : The system to be controlled (uint8_t)
roll                    : roll (float)
pitch                   : pitch (float)
yaw                     : yaw (float)
thrust                  : thrust (float)
roll_manual             : roll control enabled auto:0, manual:1 (uint8_t)
pitch_manual            : pitch auto:0, manual:1 (uint8_t)
yaw_manual              : yaw auto:0, manual:1 (uint8_t)
thrust_manual           : thrust auto:0, manual:1 (uint8_t)
def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual):
target                  : The system to be controlled (uint8_t)
roll                    : roll (float)
pitch                   : pitch (float)
yaw                     : yaw (float)
thrust                  : thrust (float)
roll_manual             : roll control enabled auto:0, manual:1 (uint8_t)
pitch_manual            : pitch auto:0, manual:1 (uint8_t)
yaw_manual              : yaw auto:0, manual:1 (uint8_t)
thrust_manual           : thrust auto:0, manual:1 (uint8_t)
def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
The RAW values of the RC channels sent to the MAV to override info
received from the RC radio. A value of -1 means no change to that
channel. A value of 0 means control of that channel should be
released back to the RC radio. The standard PPM modulation is as
follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual
receivers/transmitters might violate this specification.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
chan1_raw               : RC channel 1 value, in microseconds (uint16_t)
chan2_raw               : RC channel 2 value, in microseconds (uint16_t)
chan3_raw               : RC channel 3 value, in microseconds (uint16_t)
chan4_raw               : RC channel 4 value, in microseconds (uint16_t)
chan5_raw               : RC channel 5 value, in microseconds (uint16_t)
chan6_raw               : RC channel 6 value, in microseconds (uint16_t)
chan7_raw               : RC channel 7 value, in microseconds (uint16_t)
chan8_raw               : RC channel 8 value, in microseconds (uint16_t)
def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw):
The RAW values of the RC channels sent to the MAV to override info
received from the RC radio. A value of -1 means no change to that
channel. A value of 0 means control of that channel should be
released back to the RC radio. The standard PPM modulation is as
follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual
receivers/transmitters might violate this specification.

target_system           : System ID (uint8_t)
target_component        : Component ID (uint8_t)
chan1_raw               : RC channel 1 value, in microseconds (uint16_t)
chan2_raw               : RC channel 2 value, in microseconds (uint16_t)
chan3_raw               : RC channel 3 value, in microseconds (uint16_t)
chan4_raw               : RC channel 4 value, in microseconds (uint16_t)
chan5_raw               : RC channel 5 value, in microseconds (uint16_t)
chan6_raw               : RC channel 6 value, in microseconds (uint16_t)
chan7_raw               : RC channel 7 value, in microseconds (uint16_t)
chan8_raw               : RC channel 8 value, in microseconds (uint16_t)
def global_position_int_encode(self, lat, lon, alt, vx, vy, vz):
The filtered global position (e.g. fused GPS and accelerometers). The
position is in GPS-frame (right-handed, Z-up)

lat                     : Latitude, expressed as * 1E7 (int32_t)
lon                     : Longitude, expressed as * 1E7 (int32_t)
alt                     : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx                      : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy                      : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz                      : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
def global_position_int_send(self, lat, lon, alt, vx, vy, vz):
The filtered global position (e.g. fused GPS and accelerometers). The
position is in GPS-frame (right-handed, Z-up)

lat                     : Latitude, expressed as * 1E7 (int32_t)
lon                     : Longitude, expressed as * 1E7 (int32_t)
alt                     : Altitude in meters, expressed as * 1000 (millimeters) (int32_t)
vx                      : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t)
vy                      : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t)
vz                      : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t)
def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb):
Metrics typically displayed on a HUD for fixed wing aircraft

airspeed                : Current airspeed in m/s (float)
groundspeed             : Current ground speed in m/s (float)
heading                 : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
throttle                : Current throttle setting in integer percent, 0 to 100 (uint16_t)
alt                     : Current altitude (MSL), in meters (float)
climb                   : Current climb rate in meters/second (float)
def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb):
Metrics typically displayed on a HUD for fixed wing aircraft

airspeed                : Current airspeed in m/s (float)
groundspeed             : Current ground speed in m/s (float)
heading                 : Current heading in degrees, in compass units (0..360, 0=north) (int16_t)
throttle                : Current throttle setting in integer percent, 0 to 100 (uint16_t)
alt                     : Current altitude (MSL), in meters (float)
climb                   : Current climb rate in meters/second (float)
def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4):
Send a command with up to four parameters to the MAV

target_system           : System which should execute the command (uint8_t)
target_component        : Component which should execute the command, 0 for all components (uint8_t)
command                 : Command ID, as defined by MAV_CMD enum. (uint8_t)
confirmation            : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
param1                  : Parameter 1, as defined by MAV_CMD enum. (float)
param2                  : Parameter 2, as defined by MAV_CMD enum. (float)
param3                  : Parameter 3, as defined by MAV_CMD enum. (float)
param4                  : Parameter 4, as defined by MAV_CMD enum. (float)
def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4):
Send a command with up to four parameters to the MAV

target_system           : System which should execute the command (uint8_t)
target_component        : Component which should execute the command, 0 for all components (uint8_t)
command                 : Command ID, as defined by MAV_CMD enum. (uint8_t)
confirmation            : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t)
param1                  : Parameter 1, as defined by MAV_CMD enum. (float)
param2                  : Parameter 2, as defined by MAV_CMD enum. (float)
param3                  : Parameter 3, as defined by MAV_CMD enum. (float)
param4                  : Parameter 4, as defined by MAV_CMD enum. (float)
def command_ack_encode(self, command, result):
Report status of a command. Includes feedback wether the command was
executed

command                 : Current airspeed in m/s (float)
result                  : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float)
def command_ack_send(self, command, result):
Report status of a command. Includes feedback wether the command was
executed

command                 : Current airspeed in m/s (float)
result                  : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float)
def optical_flow_encode(self, time, flow_x, flow_y, quality, ground_distance):
Optical flow from a flow sensor (e.g. optical mouse sensor)

time                    : Timestamp (UNIX) (uint64_t)
flow_x                  : Flow in pixels in x-sensor direction (uint8_t)
flow_y                  : Flow in pixels in y-sensor direction (uint8_t)
quality                 : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
ground_distance         : Ground distance in meters (float)
def optical_flow_send(self, time, flow_x, flow_y, quality, ground_distance):
Optical flow from a flow sensor (e.g. optical mouse sensor)

time                    : Timestamp (UNIX) (uint64_t)
flow_x                  : Flow in pixels in x-sensor direction (uint8_t)
flow_y                  : Flow in pixels in y-sensor direction (uint8_t)
quality                 : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t)
ground_distance         : Ground distance in meters (float)
def debug_vect_encode(self, name, usec, x, y, z):
name                    : Name (char)
usec                    : Timestamp (uint64_t)
x                       : x (float)
y                       : y (float)
z                       : z (float)
def debug_vect_send(self, name, usec, x, y, z):
name                    : Name (char)
usec                    : Timestamp (uint64_t)
x                       : x (float)
y                       : y (float)
z                       : z (float)
def named_value_float_encode(self, name, value):
Send a key-value pair as float. The use of this message is discouraged
for normal packets, but a quite efficient way for testing new
messages and getting experimental debug output.

name                    : Name of the debug variable (char)
value                   : Floating point value (float)
def named_value_float_send(self, name, value):
Send a key-value pair as float. The use of this message is discouraged
for normal packets, but a quite efficient way for testing new
messages and getting experimental debug output.

name                    : Name of the debug variable (char)
value                   : Floating point value (float)
def named_value_int_encode(self, name, value):
Send a key-value pair as integer. The use of this message is
discouraged for normal packets, but a quite efficient way for
testing new messages and getting experimental debug output.

name                    : Name of the debug variable (char)
value                   : Signed integer value (int32_t)
def named_value_int_send(self, name, value):
Send a key-value pair as integer. The use of this message is
discouraged for normal packets, but a quite efficient way for
testing new messages and getting experimental debug output.

name                    : Name of the debug variable (char)
value                   : Signed integer value (int32_t)
def statustext_encode(self, severity, text):
Status text message. These messages are printed in yellow in the COMM
console of QGroundControl. WARNING: They consume quite some
bandwidth, so use only for important status and error messages. If
implemented wisely, these messages are buffered on the MCU and sent
only at a limited rate (e.g. 10 Hz).

severity                : Severity of status, 0 = info message, 255 = critical fault (uint8_t)
text                    : Status text message, without null termination character (int8_t)
def statustext_send(self, severity, text):
Status text message. These messages are printed in yellow in the COMM
console of QGroundControl. WARNING: They consume quite some
bandwidth, so use only for important status and error messages. If
implemented wisely, these messages are buffered on the MCU and sent
only at a limited rate (e.g. 10 Hz).

severity                : Severity of status, 0 = info message, 255 = critical fault (uint8_t)
text                    : Status text message, without null termination character (int8_t)
def debug_encode(self, ind, value):
Send a debug value. The index is used to discriminate between values.
These values show up in the plot of QGroundControl as DEBUG N.

ind                     : index of debug variable (uint8_t)
value                   : DEBUG value (float)
def debug_send(self, ind, value):
Send a debug value. The index is used to discriminate between values.
These values show up in the plot of QGroundControl as DEBUG N.

ind                     : index of debug variable (uint8_t)
value                   : DEBUG value (float)
API Documentation for PyMAVLink, generated by pydoctor at 2011-08-20 08:50:37.