mavlink v0.7.0 APM.Types View Source

Link to this section Summary

Types

Enumeration of the ADSB altimeter types

ADSB classification for the type of vehicle emitting the transponder signal

These flags indicate status such as data validity of each data source. Set = data valid

Camera capability flags (Bitmap)

Camera Modes.

A mapping of copter flight modes for custom_mode field of heartbeat.

Deepstall flight stage.

Bus types for device operations.

Flags in EKF_STATUS message.

An atom representing a MAVLink enumeration type

An atom representing a MAVLink enumeration type value

Flags in EKF_STATUS message

Measurement unit of field value

These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65.

Type of GPS fix

Gripper actions.

Type of landing target

Micro air vehicle / autopilot classes. This identifies the individual model.

Enumeration for battery charge states.

Enumeration of battery functions

Enumeration of battery types

ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.

Possible actions an aircraft can take to avoid a collision.

Source of information about this collision.

Aircraft-rated danger from this threat.

Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.

A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.

Enumeration of distance sensor types

Bitmap of options for the MAV_CMD_DO_REPOSITION

Enumeration of estimator types

Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.

Enumeration of landed detector states

Result of mission operation (in a MISSION_ACK message).

Type of mission items being requested/sent in mission protocol.

These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.

These flags encode the MAV mode.

These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.

Enumeration of possible mount operation modes

Specifies the datatype of a MAVLink parameter.

Power supply status flags (bitmask)

Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.

Special ACK block numbers control activation of dataflash log streaming.

Possible remote log data block statuses.

result from a mavlink command

THIS INTERFACE IS DEPRECATED AS OF JANUARY 2018. Please use MAVCMD_DO_SET_ROI* messages instead. The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI).

Enumeration of sensor orientation, according to its rotations

Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.

These encode the sensors whose status is sent as part of the SYS_STATUS message.

MAVLINK system type. All components in a system should report this type in their HEARTBEAT.

Enumeration of VTOL states

A MAVLink message

A mapping of plane flight modes for custom_mode field of heartbeat.

Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration.

Precision land modes (used in MAV_CMD_NAV_LAND).

Flags in RALLY_POINT message.

RC type

A mapping of rover flight modes for custom_mode field of heartbeat.

RTK GPS baseline coordinate system, used for RTK corrections

SERIAL_CONTROL device types

SERIAL_CONTROL flags (bitmask)

Flags to indicate the status of camera storage.

A mapping of sub flight modes for custom_mode field of heartbeat.

A mapping of antenna tracker flight modes for custom_mode field of heartbeat.

Generalized UAVCAN node health

Generalized UAVCAN node mode

Emergency status encoding

Definitions for aircraft size

GPS lataral offset encoding

GPS longitudinal offset encoding

Status for ADS-B transponder dynamic input

State flags for ADS-B transponder dynamic report

Transceiver RF control flags for ADS-B transponder dynamic reports

Status flags for ADS-B transponder dynamic output

Direction of VTOL transition

Winch actions.

Link to this section Types

Link to this type

accelcal_vehicle_pos() View Source
accelcal_vehicle_pos() ::
  :accelcal_vehicle_pos_level
  | :accelcal_vehicle_pos_left
  | :accelcal_vehicle_pos_right
  | :accelcal_vehicle_pos_nosedown
  | :accelcal_vehicle_pos_noseup
  | :accelcal_vehicle_pos_back
  | :accelcal_vehicle_pos_success
  | :accelcal_vehicle_pos_failed

Link to this type

adsb_altitude_type() View Source
adsb_altitude_type() ::
  :adsb_altitude_type_pressure_qnh | :adsb_altitude_type_geometric

Enumeration of the ADSB altimeter types

Link to this type

adsb_emitter_type() View Source
adsb_emitter_type() ::
  :adsb_emitter_type_no_info
  | :adsb_emitter_type_light
  | :adsb_emitter_type_small
  | :adsb_emitter_type_large
  | :adsb_emitter_type_high_vortex_large
  | :adsb_emitter_type_heavy
  | :adsb_emitter_type_highly_manuv
  | :adsb_emitter_type_rotocraft
  | :adsb_emitter_type_unassigned
  | :adsb_emitter_type_glider
  | :adsb_emitter_type_lighter_air
  | :adsb_emitter_type_parachute
  | :adsb_emitter_type_ultra_light
  | :adsb_emitter_type_unassigned2
  | :adsb_emitter_type_uav
  | :adsb_emitter_type_space
  | :adsb_emitter_type_unassgined3
  | :adsb_emitter_type_emergency_surface
  | :adsb_emitter_type_service_surface
  | :adsb_emitter_type_point_obstacle

ADSB classification for the type of vehicle emitting the transponder signal

Link to this type

adsb_flags() View Source
adsb_flags() ::
  :adsb_flags_valid_coords
  | :adsb_flags_valid_altitude
  | :adsb_flags_valid_heading
  | :adsb_flags_valid_velocity
  | :adsb_flags_valid_callsign
  | :adsb_flags_valid_squawk
  | :adsb_flags_simulated

These flags indicate status such as data validity of each data source. Set = data valid

Link to this type

camera_cap_flags() View Source
camera_cap_flags() ::
  :camera_cap_flags_capture_video
  | :camera_cap_flags_capture_image
  | :camera_cap_flags_has_modes
  | :camera_cap_flags_can_capture_image_in_video_mode
  | :camera_cap_flags_can_capture_video_in_image_mode
  | :camera_cap_flags_has_image_survey_mode
  | :camera_cap_flags_has_basic_zoom
  | :camera_cap_flags_has_basic_focus
  | :camera_cap_flags_has_video_stream

Camera capability flags (Bitmap)

Link to this type

camera_feedback_flags() View Source
camera_feedback_flags() ::
  :camera_feedback_photo
  | :camera_feedback_video
  | :camera_feedback_badexposure
  | :camera_feedback_closedloop
  | :camera_feedback_openloop

Link to this type

camera_mode() View Source
camera_mode() ::
  :camera_mode_image | :camera_mode_video | :camera_mode_image_survey

Camera Modes.

Link to this type

camera_status_types() View Source
camera_status_types() ::
  :camera_status_type_heartbeat
  | :camera_status_type_trigger
  | :camera_status_type_disconnect
  | :camera_status_type_error
  | :camera_status_type_lowbatt
  | :camera_status_type_lowstore
  | :camera_status_type_lowstorev

Link to this type

copter_mode() View Source
copter_mode() ::
  :copter_mode_stabilize
  | :copter_mode_acro
  | :copter_mode_alt_hold
  | :copter_mode_auto
  | :copter_mode_guided
  | :copter_mode_loiter
  | :copter_mode_rtl
  | :copter_mode_circle
  | :copter_mode_land
  | :copter_mode_drift
  | :copter_mode_sport
  | :copter_mode_flip
  | :copter_mode_autotune
  | :copter_mode_poshold
  | :copter_mode_brake
  | :copter_mode_throw
  | :copter_mode_avoid_adsb
  | :copter_mode_guided_nogps
  | :copter_mode_smart_rtl

A mapping of copter flight modes for custom_mode field of heartbeat.

Link to this type

deepstall_stage() View Source
deepstall_stage() ::
  :deepstall_stage_fly_to_landing
  | :deepstall_stage_estimate_wind
  | :deepstall_stage_wait_for_breakout
  | :deepstall_stage_fly_to_arc
  | :deepstall_stage_arc
  | :deepstall_stage_approach
  | :deepstall_stage_land

Deepstall flight stage.

Link to this type

device_op_bustype() View Source
device_op_bustype() :: :device_op_bustype_i2c | :device_op_bustype_spi

Bus types for device operations.

Link to this type

ekf_status_flags() View Source
ekf_status_flags() ::
  :ekf_attitude
  | :ekf_velocity_horiz
  | :ekf_velocity_vert
  | :ekf_pos_horiz_rel
  | :ekf_pos_horiz_abs
  | :ekf_pos_vert_abs
  | :ekf_pos_vert_agl
  | :ekf_const_pos_mode
  | :ekf_pred_pos_horiz_rel
  | :ekf_pred_pos_horiz_abs

Flags in EKF_STATUS message.

Link to this type

enum_type() View Source
enum_type() ::
  :accelcal_vehicle_pos
  | :adsb_altitude_type
  | :adsb_emitter_type
  | :adsb_flags
  | :camera_cap_flags
  | :camera_feedback_flags
  | :camera_mode
  | :camera_status_types
  | :copter_mode
  | :deepstall_stage
  | :device_op_bustype
  | :ekf_status_flags
  | :estimator_status_flags
  | :fence_action
  | :fence_breach
  | :firmware_version_type
  | :gimbal_axis
  | :gimbal_axis_calibration_required
  | :gimbal_axis_calibration_status
  | :gopro_burst_rate
  | :gopro_capture_mode
  | :gopro_charging
  | :gopro_command
  | :gopro_field_of_view
  | :gopro_frame_rate
  | :gopro_heartbeat_flags
  | :gopro_heartbeat_status
  | :gopro_model
  | :gopro_photo_resolution
  | :gopro_protune_colour
  | :gopro_protune_exposure
  | :gopro_protune_gain
  | :gopro_protune_sharpness
  | :gopro_protune_white_balance
  | :gopro_request_status
  | :gopro_resolution
  | :gopro_video_settings_flags
  | :gps_fix_type
  | :gps_input_ignore_flags
  | :gripper_actions
  | :icarous_fms_state
  | :icarous_track_band_types
  | :landing_target_type
  | :led_control_pattern
  | :limit_module
  | :limits_state
  | :mag_cal_status
  | :mav_arm_auth_denied_reason
  | :mav_autopilot
  | :mav_battery_charge_state
  | :mav_battery_function
  | :mav_battery_type
  | :mav_cmd
  | :mav_cmd_ack
  | :mav_collision_action
  | :mav_collision_src
  | :mav_collision_threat_level
  | :mav_component
  | :mav_data_stream
  | :mav_distance_sensor
  | :mav_do_reposition_flags
  | :mav_estimator_type
  | :mav_frame
  | :mav_goto
  | :mav_landed_state
  | :mav_mission_result
  | :mav_mission_type
  | :mav_mode
  | :mav_mode_flag
  | :mav_mode_flag_decode_position
  | :mav_mode_gimbal
  | :mav_mount_mode
  | :mav_param_type
  | :mav_power_status
  | :mav_protocol_capability
  | :mav_remote_log_data_block_commands
  | :mav_remote_log_data_block_statuses
  | :mav_result
  | :mav_roi
  | :mav_sensor_orientation
  | :mav_severity
  | :mav_state
  | :mav_sys_status_sensor
  | :mav_type
  | :mav_vtol_state
  | :mavlink_data_stream_type
  | :motor_test_order
  | :motor_test_throttle_type
  | :parachute_action
  | :pid_tuning_axis
  | :plane_mode
  | :position_target_typemask
  | :precision_land_mode
  | :rally_flags
  | :rc_type
  | :rover_mode
  | :rtk_baseline_coordinate_system
  | :serial_control_dev
  | :serial_control_flag
  | :storage_status
  | :sub_mode
  | :tracker_mode
  | :uavcan_node_health
  | :uavcan_node_mode
  | :uavionix_adsb_emergency_status
  | :uavionix_adsb_out_cfg_aircraft_size
  | :uavionix_adsb_out_cfg_gps_offset_lat
  | :uavionix_adsb_out_cfg_gps_offset_lon
  | :uavionix_adsb_out_dynamic_gps_fix
  | :uavionix_adsb_out_dynamic_state
  | :uavionix_adsb_out_rf_select
  | :uavionix_adsb_rf_health
  | :vtol_transition_heading
  | :winch_actions

An atom representing a MAVLink enumeration type

Link to this type

enum_value() View Source
enum_value() ::
  accelcal_vehicle_pos()
  | adsb_altitude_type()
  | adsb_emitter_type()
  | adsb_flags()
  | camera_cap_flags()
  | camera_feedback_flags()
  | camera_mode()
  | camera_status_types()
  | copter_mode()
  | deepstall_stage()
  | device_op_bustype()
  | ekf_status_flags()
  | estimator_status_flags()
  | fence_action()
  | fence_breach()
  | firmware_version_type()
  | gimbal_axis()
  | gimbal_axis_calibration_required()
  | gimbal_axis_calibration_status()
  | gopro_burst_rate()
  | gopro_capture_mode()
  | gopro_charging()
  | gopro_command()
  | gopro_field_of_view()
  | gopro_frame_rate()
  | gopro_heartbeat_flags()
  | gopro_heartbeat_status()
  | gopro_model()
  | gopro_photo_resolution()
  | gopro_protune_colour()
  | gopro_protune_exposure()
  | gopro_protune_gain()
  | gopro_protune_sharpness()
  | gopro_protune_white_balance()
  | gopro_request_status()
  | gopro_resolution()
  | gopro_video_settings_flags()
  | gps_fix_type()
  | gps_input_ignore_flags()
  | gripper_actions()
  | icarous_fms_state()
  | icarous_track_band_types()
  | landing_target_type()
  | led_control_pattern()
  | limit_module()
  | limits_state()
  | mag_cal_status()
  | mav_arm_auth_denied_reason()
  | mav_autopilot()
  | mav_battery_charge_state()
  | mav_battery_function()
  | mav_battery_type()
  | mav_cmd()
  | mav_cmd_ack()
  | mav_collision_action()
  | mav_collision_src()
  | mav_collision_threat_level()
  | mav_component()
  | mav_data_stream()
  | mav_distance_sensor()
  | mav_do_reposition_flags()
  | mav_estimator_type()
  | mav_frame()
  | mav_goto()
  | mav_landed_state()
  | mav_mission_result()
  | mav_mission_type()
  | mav_mode()
  | mav_mode_flag()
  | mav_mode_flag_decode_position()
  | mav_mode_gimbal()
  | mav_mount_mode()
  | mav_param_type()
  | mav_power_status()
  | mav_protocol_capability()
  | mav_remote_log_data_block_commands()
  | mav_remote_log_data_block_statuses()
  | mav_result()
  | mav_roi()
  | mav_sensor_orientation()
  | mav_severity()
  | mav_state()
  | mav_sys_status_sensor()
  | mav_type()
  | mav_vtol_state()
  | mavlink_data_stream_type()
  | motor_test_order()
  | motor_test_throttle_type()
  | parachute_action()
  | pid_tuning_axis()
  | plane_mode()
  | position_target_typemask()
  | precision_land_mode()
  | rally_flags()
  | rc_type()
  | rover_mode()
  | rtk_baseline_coordinate_system()
  | serial_control_dev()
  | serial_control_flag()
  | storage_status()
  | sub_mode()
  | tracker_mode()
  | uavcan_node_health()
  | uavcan_node_mode()
  | uavionix_adsb_emergency_status()
  | uavionix_adsb_out_cfg_aircraft_size()
  | uavionix_adsb_out_cfg_gps_offset_lat()
  | uavionix_adsb_out_cfg_gps_offset_lon()
  | uavionix_adsb_out_dynamic_gps_fix()
  | uavionix_adsb_out_dynamic_state()
  | uavionix_adsb_out_rf_select()
  | uavionix_adsb_rf_health()
  | vtol_transition_heading()
  | winch_actions()

An atom representing a MAVLink enumeration type value

Link to this type

estimator_status_flags() View Source
estimator_status_flags() ::
  :estimator_attitude
  | :estimator_velocity_horiz
  | :estimator_velocity_vert
  | :estimator_pos_horiz_rel
  | :estimator_pos_horiz_abs
  | :estimator_pos_vert_abs
  | :estimator_pos_vert_agl
  | :estimator_const_pos_mode
  | :estimator_pred_pos_horiz_rel
  | :estimator_pred_pos_horiz_abs
  | :estimator_gps_glitch
  | :estimator_accel_error

Flags in EKF_STATUS message

Link to this type

fence_action() View Source
fence_action() ::
  :fence_action_none
  | :fence_action_guided
  | :fence_action_report
  | :fence_action_guided_thr_pass
  | :fence_action_rtl

Link to this type

fence_breach() View Source
fence_breach() ::
  :fence_breach_none
  | :fence_breach_minalt
  | :fence_breach_maxalt
  | :fence_breach_boundary

Link to this type

field_unit() View Source
field_unit() ::
  :%
  | :"MiB/s"
  | :"bits/s"
  | :"c%"
  | :"cm/s"
  | :"cm^2"
  | :"d%"
  | :"deg/s"
  | :"m/s"
  | :"m/s/s"
  | :"mm/s"
  | :"mrad/s"
  | :"rad/s"
  | :A
  | :Hz
  | :MiB
  | :Pa
  | :V
  | :bytes
  | :cA
  | :cV
  | :cdeg
  | :cdegC
  | :cm
  | :dB
  | :deg
  | :degC
  | :degE5
  | :degE7
  | :dpix
  | :ds
  | :gauss
  | :hJ
  | :hPa
  | :m
  | :mAh
  | :mG
  | :mT
  | :mV
  | :mbar
  | :mgauss
  | :mm
  | :ms
  | :pix
  | :rad
  | :rpm
  | :s
  | :us

Measurement unit of field value

Link to this type

firmware_version_type() View Source
firmware_version_type() ::
  :firmware_version_type_dev
  | :firmware_version_type_alpha
  | :firmware_version_type_beta
  | :firmware_version_type_rc
  | :firmware_version_type_official

These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65.

Link to this type

gimbal_axis() View Source
gimbal_axis() :: :gimbal_axis_yaw | :gimbal_axis_pitch | :gimbal_axis_roll

Link to this type

gimbal_axis_calibration_required() View Source
gimbal_axis_calibration_required() ::
  :gimbal_axis_calibration_required_unknown
  | :gimbal_axis_calibration_required_true
  | :gimbal_axis_calibration_required_false

Link to this type

gimbal_axis_calibration_status() View Source
gimbal_axis_calibration_status() ::
  :gimbal_axis_calibration_status_in_progress
  | :gimbal_axis_calibration_status_succeeded
  | :gimbal_axis_calibration_status_failed

Link to this type

gopro_burst_rate() View Source
gopro_burst_rate() ::
  :gopro_burst_rate_3_in_1_second
  | :gopro_burst_rate_5_in_1_second
  | :gopro_burst_rate_10_in_1_second
  | :gopro_burst_rate_10_in_2_second
  | :gopro_burst_rate_10_in_3_second
  | :gopro_burst_rate_30_in_1_second
  | :gopro_burst_rate_30_in_2_second
  | :gopro_burst_rate_30_in_3_second
  | :gopro_burst_rate_30_in_6_second

Link to this type

gopro_capture_mode() View Source
gopro_capture_mode() ::
  :gopro_capture_mode_video
  | :gopro_capture_mode_photo
  | :gopro_capture_mode_burst
  | :gopro_capture_mode_time_lapse
  | :gopro_capture_mode_multi_shot
  | :gopro_capture_mode_playback
  | :gopro_capture_mode_setup
  | :gopro_capture_mode_unknown

Link to this type

gopro_charging() View Source
gopro_charging() :: :gopro_charging_disabled | :gopro_charging_enabled

Link to this type

gopro_command() View Source
gopro_command() ::
  :gopro_command_power
  | :gopro_command_capture_mode
  | :gopro_command_shutter
  | :gopro_command_battery
  | :gopro_command_model
  | :gopro_command_video_settings
  | :gopro_command_low_light
  | :gopro_command_photo_resolution
  | :gopro_command_photo_burst_rate
  | :gopro_command_protune
  | :gopro_command_protune_white_balance
  | :gopro_command_protune_colour
  | :gopro_command_protune_gain
  | :gopro_command_protune_sharpness
  | :gopro_command_protune_exposure
  | :gopro_command_time
  | :gopro_command_charging

Link to this type

gopro_field_of_view() View Source
gopro_field_of_view() ::
  :gopro_field_of_view_wide
  | :gopro_field_of_view_medium
  | :gopro_field_of_view_narrow

Link to this type

gopro_frame_rate() View Source
gopro_frame_rate() ::
  :gopro_frame_rate_12
  | :gopro_frame_rate_15
  | :gopro_frame_rate_24
  | :gopro_frame_rate_25
  | :gopro_frame_rate_30
  | :gopro_frame_rate_48
  | :gopro_frame_rate_50
  | :gopro_frame_rate_60
  | :gopro_frame_rate_80
  | :gopro_frame_rate_90
  | :gopro_frame_rate_100
  | :gopro_frame_rate_120
  | :gopro_frame_rate_240
  | :gopro_frame_rate_12_5

Link to this type

gopro_heartbeat_flags() View Source
gopro_heartbeat_flags() :: :gopro_flag_recording

Link to this type

gopro_heartbeat_status() View Source
gopro_heartbeat_status() ::
  :gopro_heartbeat_status_disconnected
  | :gopro_heartbeat_status_incompatible
  | :gopro_heartbeat_status_connected
  | :gopro_heartbeat_status_error

Link to this type

gopro_model() View Source
gopro_model() ::
  :gopro_model_unknown
  | :gopro_model_hero_3_plus_silver
  | :gopro_model_hero_3_plus_black
  | :gopro_model_hero_4_silver
  | :gopro_model_hero_4_black

Link to this type

gopro_photo_resolution() View Source
gopro_photo_resolution() ::
  :gopro_photo_resolution_5mp_medium
  | :gopro_photo_resolution_7mp_medium
  | :gopro_photo_resolution_7mp_wide
  | :gopro_photo_resolution_10mp_wide
  | :gopro_photo_resolution_12mp_wide

Link to this type

gopro_protune_colour() View Source
gopro_protune_colour() ::
  :gopro_protune_colour_standard | :gopro_protune_colour_neutral

Link to this type

gopro_protune_exposure() View Source
gopro_protune_exposure() ::
  :gopro_protune_exposure_neg_5_0
  | :gopro_protune_exposure_neg_4_5
  | :gopro_protune_exposure_neg_4_0
  | :gopro_protune_exposure_neg_3_5
  | :gopro_protune_exposure_neg_3_0
  | :gopro_protune_exposure_neg_2_5
  | :gopro_protune_exposure_neg_2_0
  | :gopro_protune_exposure_neg_1_5
  | :gopro_protune_exposure_neg_1_0
  | :gopro_protune_exposure_neg_0_5
  | :gopro_protune_exposure_zero
  | :gopro_protune_exposure_pos_0_5
  | :gopro_protune_exposure_pos_1_0
  | :gopro_protune_exposure_pos_1_5
  | :gopro_protune_exposure_pos_2_0
  | :gopro_protune_exposure_pos_2_5
  | :gopro_protune_exposure_pos_3_0
  | :gopro_protune_exposure_pos_3_5
  | :gopro_protune_exposure_pos_4_0
  | :gopro_protune_exposure_pos_4_5
  | :gopro_protune_exposure_pos_5_0

Link to this type

gopro_protune_gain() View Source
gopro_protune_gain() ::
  :gopro_protune_gain_400
  | :gopro_protune_gain_800
  | :gopro_protune_gain_1600
  | :gopro_protune_gain_3200
  | :gopro_protune_gain_6400

Link to this type

gopro_protune_sharpness() View Source
gopro_protune_sharpness() ::
  :gopro_protune_sharpness_low
  | :gopro_protune_sharpness_medium
  | :gopro_protune_sharpness_high

Link to this type

gopro_protune_white_balance() View Source
gopro_protune_white_balance() ::
  :gopro_protune_white_balance_auto
  | :gopro_protune_white_balance_3000k
  | :gopro_protune_white_balance_5500k
  | :gopro_protune_white_balance_6500k
  | :gopro_protune_white_balance_raw

Link to this type

gopro_request_status() View Source
gopro_request_status() :: :gopro_request_success | :gopro_request_failed

Link to this type

gopro_resolution() View Source
gopro_resolution() ::
  :gopro_resolution_480p
  | :gopro_resolution_720p
  | :gopro_resolution_960p
  | :gopro_resolution_1080p
  | :gopro_resolution_1440p
  | :gopro_resolution_2_7k_17_9
  | :gopro_resolution_2_7k_16_9
  | :gopro_resolution_2_7k_4_3
  | :gopro_resolution_4k_16_9
  | :gopro_resolution_4k_17_9
  | :gopro_resolution_720p_superview
  | :gopro_resolution_1080p_superview
  | :gopro_resolution_2_7k_superview
  | :gopro_resolution_4k_superview

Link to this type

gopro_video_settings_flags() View Source
gopro_video_settings_flags() :: :gopro_video_settings_tv_mode

Link to this type

gps_fix_type() View Source
gps_fix_type() ::
  :gps_fix_type_no_gps
  | :gps_fix_type_no_fix
  | :gps_fix_type_2d_fix
  | :gps_fix_type_3d_fix
  | :gps_fix_type_dgps
  | :gps_fix_type_rtk_float
  | :gps_fix_type_rtk_fixed
  | :gps_fix_type_static
  | :gps_fix_type_ppp

Type of GPS fix

Link to this type

gps_input_ignore_flags() View Source
gps_input_ignore_flags() ::
  :gps_input_ignore_flag_alt
  | :gps_input_ignore_flag_hdop
  | :gps_input_ignore_flag_vdop
  | :gps_input_ignore_flag_vel_horiz
  | :gps_input_ignore_flag_vel_vert
  | :gps_input_ignore_flag_speed_accuracy
  | :gps_input_ignore_flag_horizontal_accuracy
  | :gps_input_ignore_flag_vertical_accuracy

Link to this type

gripper_actions() View Source
gripper_actions() :: :gripper_action_release | :gripper_action_grab

Gripper actions.

Link to this type

icarous_fms_state() View Source
icarous_fms_state() ::
  :icarous_fms_state_idle
  | :icarous_fms_state_takeoff
  | :icarous_fms_state_climb
  | :icarous_fms_state_cruise
  | :icarous_fms_state_approach
  | :icarous_fms_state_land

Link to this type

icarous_track_band_types() View Source
icarous_track_band_types() ::
  :icarous_track_band_type_none
  | :icarous_track_band_type_near
  | :icarous_track_band_type_recovery

Link to this type

landing_target_type() View Source
landing_target_type() ::
  :landing_target_type_light_beacon
  | :landing_target_type_radio_beacon
  | :landing_target_type_vision_fiducial
  | :landing_target_type_vision_other

Type of landing target

Link to this type

led_control_pattern() View Source
led_control_pattern() ::
  :led_control_pattern_off
  | :led_control_pattern_firmwareupdate
  | :led_control_pattern_custom

Link to this type

limit_module() View Source
limit_module() :: :limit_gpslock | :limit_geofence | :limit_altitude

Link to this type

limits_state() View Source
limits_state() ::
  :limits_init
  | :limits_disabled
  | :limits_enabled
  | :limits_triggered
  | :limits_recovering
  | :limits_recovered

Link to this type

mag_cal_status() View Source
mag_cal_status() ::
  :mag_cal_not_started
  | :mag_cal_waiting_to_start
  | :mag_cal_running_step_one
  | :mag_cal_running_step_two
  | :mag_cal_success
  | :mag_cal_failed
  | :mag_cal_bad_orientation

Link to this type

mav_arm_auth_denied_reason() View Source
mav_arm_auth_denied_reason() ::
  :mav_arm_auth_denied_reason_generic
  | :mav_arm_auth_denied_reason_none
  | :mav_arm_auth_denied_reason_invalid_waypoint
  | :mav_arm_auth_denied_reason_timeout
  | :mav_arm_auth_denied_reason_airspace_in_use
  | :mav_arm_auth_denied_reason_bad_weather

Link to this type

mav_autopilot() View Source
mav_autopilot() ::
  :mav_autopilot_generic
  | :mav_autopilot_reserved
  | :mav_autopilot_slugs
  | :mav_autopilot_ardupilotmega
  | :mav_autopilot_openpilot
  | :mav_autopilot_generic_waypoints_only
  | :mav_autopilot_generic_waypoints_and_simple_navigation_only
  | :mav_autopilot_generic_mission_full
  | :mav_autopilot_invalid
  | :mav_autopilot_ppz
  | :mav_autopilot_udb
  | :mav_autopilot_fp
  | :mav_autopilot_px4
  | :mav_autopilot_smaccmpilot
  | :mav_autopilot_autoquad
  | :mav_autopilot_armazila
  | :mav_autopilot_aerob
  | :mav_autopilot_asluav
  | :mav_autopilot_smartap
  | :mav_autopilot_airrails

Micro air vehicle / autopilot classes. This identifies the individual model.

Link to this type

mav_battery_charge_state() View Source
mav_battery_charge_state() ::
  :mav_battery_charge_state_undefined
  | :mav_battery_charge_state_ok
  | :mav_battery_charge_state_low
  | :mav_battery_charge_state_critical
  | :mav_battery_charge_state_emergency
  | :mav_battery_charge_state_failed
  | :mav_battery_charge_state_unhealthy
  | :mav_battery_charge_state_charging

Enumeration for battery charge states.

Link to this type

mav_battery_function() View Source
mav_battery_function() ::
  :mav_battery_function_unknown
  | :mav_battery_function_all
  | :mav_battery_function_propulsion
  | :mav_battery_function_avionics
  | :mav_battery_type_payload

Enumeration of battery functions

Link to this type

mav_battery_type() View Source
mav_battery_type() ::
  :mav_battery_type_unknown
  | :mav_battery_type_lipo
  | :mav_battery_type_life
  | :mav_battery_type_lion
  | :mav_battery_type_nimh

Enumeration of battery types

Link to this type

mav_cmd() View Source
mav_cmd() ::
  :mav_cmd_nav_waypoint
  | :mav_cmd_nav_loiter_unlim
  | :mav_cmd_nav_loiter_turns
  | :mav_cmd_nav_loiter_time
  | :mav_cmd_nav_return_to_launch
  | :mav_cmd_nav_land
  | :mav_cmd_nav_takeoff
  | :mav_cmd_nav_land_local
  | :mav_cmd_nav_takeoff_local
  | :mav_cmd_nav_follow
  | :mav_cmd_nav_continue_and_change_alt
  | :mav_cmd_nav_loiter_to_alt
  | :mav_cmd_do_follow
  | :mav_cmd_do_follow_reposition
  | :mav_cmd_nav_roi
  | :mav_cmd_nav_pathplanning
  | :mav_cmd_nav_spline_waypoint
  | :mav_cmd_nav_altitude_wait
  | :mav_cmd_nav_vtol_takeoff
  | :mav_cmd_nav_vtol_land
  | :mav_cmd_nav_guided_enable
  | :mav_cmd_nav_delay
  | :mav_cmd_nav_payload_place
  | :mav_cmd_nav_last
  | :mav_cmd_condition_delay
  | :mav_cmd_condition_change_alt
  | :mav_cmd_condition_distance
  | :mav_cmd_condition_yaw
  | :mav_cmd_condition_last
  | :mav_cmd_do_set_mode
  | :mav_cmd_do_jump
  | :mav_cmd_do_change_speed
  | :mav_cmd_do_set_home
  | :mav_cmd_do_set_parameter
  | :mav_cmd_do_set_relay
  | :mav_cmd_do_repeat_relay
  | :mav_cmd_do_set_servo
  | :mav_cmd_do_repeat_servo
  | :mav_cmd_do_flighttermination
  | :mav_cmd_do_change_altitude
  | :mav_cmd_do_land_start
  | :mav_cmd_do_rally_land
  | :mav_cmd_do_go_around
  | :mav_cmd_do_reposition
  | :mav_cmd_do_pause_continue
  | :mav_cmd_do_set_reverse
  | :mav_cmd_do_set_roi_location
  | :mav_cmd_do_set_roi_wpnext_offset
  | :mav_cmd_do_set_roi_none
  | :mav_cmd_do_control_video
  | :mav_cmd_do_set_roi
  | :mav_cmd_do_digicam_configure
  | :mav_cmd_do_digicam_control
  | :mav_cmd_do_mount_configure
  | :mav_cmd_do_mount_control
  | :mav_cmd_do_set_cam_trigg_dist
  | :mav_cmd_do_fence_enable
  | :mav_cmd_do_parachute
  | :mav_cmd_do_motor_test
  | :mav_cmd_do_inverted_flight
  | :mav_cmd_do_gripper
  | :mav_cmd_do_autotune_enable
  | :mav_cmd_nav_set_yaw_speed
  | :mav_cmd_do_set_cam_trigg_interval
  | :mav_cmd_do_mount_control_quat
  | :mav_cmd_do_guided_master
  | :mav_cmd_do_guided_limits
  | :mav_cmd_do_engine_control
  | :mav_cmd_do_set_mission_current
  | :mav_cmd_do_last
  | :mav_cmd_preflight_calibration
  | :mav_cmd_preflight_set_sensor_offsets
  | :mav_cmd_preflight_uavcan
  | :mav_cmd_preflight_storage
  | :mav_cmd_preflight_reboot_shutdown
  | :mav_cmd_override_goto
  | :mav_cmd_mission_start
  | :mav_cmd_component_arm_disarm
  | :mav_cmd_get_home_position
  | :mav_cmd_start_rx_pair
  | :mav_cmd_get_message_interval
  | :mav_cmd_set_message_interval
  | :mav_cmd_request_message
  | :mav_cmd_request_autopilot_capabilities
  | :mav_cmd_request_camera_information
  | :mav_cmd_request_camera_settings
  | :mav_cmd_request_storage_information
  | :mav_cmd_storage_format
  | :mav_cmd_request_camera_capture_status
  | :mav_cmd_request_flight_information
  | :mav_cmd_reset_camera_settings
  | :mav_cmd_set_camera_mode
  | :mav_cmd_jump_tag
  | :mav_cmd_do_jump_tag
  | :mav_cmd_image_start_capture
  | :mav_cmd_image_stop_capture
  | :mav_cmd_do_trigger_control
  | :mav_cmd_video_start_capture
  | :mav_cmd_video_stop_capture
  | :mav_cmd_logging_start
  | :mav_cmd_logging_stop
  | :mav_cmd_airframe_configuration
  | :mav_cmd_control_high_latency
  | :mav_cmd_panorama_create
  | :mav_cmd_do_vtol_transition
  | :mav_cmd_arm_authorization_request
  | :mav_cmd_set_guided_submode_standard
  | :mav_cmd_set_guided_submode_circle
  | :mav_cmd_nav_fence_return_point
  | :mav_cmd_nav_fence_polygon_vertex_inclusion
  | :mav_cmd_nav_fence_polygon_vertex_exclusion
  | :mav_cmd_nav_fence_circle_inclusion
  | :mav_cmd_nav_fence_circle_exclusion
  | :mav_cmd_nav_rally_point
  | :mav_cmd_uavcan_get_node_info
  | :mav_cmd_payload_prepare_deploy
  | :mav_cmd_payload_control_deploy
  | :mav_cmd_waypoint_user_1
  | :mav_cmd_waypoint_user_2
  | :mav_cmd_waypoint_user_3
  | :mav_cmd_waypoint_user_4
  | :mav_cmd_waypoint_user_5
  | :mav_cmd_spatial_user_1
  | :mav_cmd_spatial_user_2
  | :mav_cmd_spatial_user_3
  | :mav_cmd_spatial_user_4
  | :mav_cmd_spatial_user_5
  | :mav_cmd_user_1
  | :mav_cmd_user_2
  | :mav_cmd_user_3
  | :mav_cmd_user_4
  | :mav_cmd_user_5
  | :mav_cmd_power_off_initiated
  | :mav_cmd_solo_btn_fly_click
  | :mav_cmd_solo_btn_fly_hold
  | :mav_cmd_solo_btn_pause_click
  | :mav_cmd_fixed_mag_cal
  | :mav_cmd_fixed_mag_cal_field
  | :mav_cmd_do_start_mag_cal
  | :mav_cmd_do_accept_mag_cal
  | :mav_cmd_do_cancel_mag_cal
  | :mav_cmd_set_factory_test_mode
  | :mav_cmd_do_send_banner
  | :mav_cmd_accelcal_vehicle_pos
  | :mav_cmd_gimbal_reset
  | :mav_cmd_gimbal_axis_calibration_status
  | :mav_cmd_gimbal_request_axis_calibration
  | :mav_cmd_gimbal_full_reset
  | :mav_cmd_do_winch
  | :mav_cmd_flash_bootloader
  | :mav_cmd_battery_reset

Link to this type

mav_cmd_ack() View Source
mav_cmd_ack() ::
  :mav_cmd_ack_ok
  | :mav_cmd_ack_err_fail
  | :mav_cmd_ack_err_access_denied
  | :mav_cmd_ack_err_not_supported
  | :mav_cmd_ack_err_coordinate_frame_not_supported
  | :mav_cmd_ack_err_coordinates_out_of_range
  | :mav_cmd_ack_err_x_lat_out_of_range
  | :mav_cmd_ack_err_y_lon_out_of_range
  | :mav_cmd_ack_err_z_alt_out_of_range

ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.

Link to this type

mav_collision_action() View Source
mav_collision_action() ::
  :mav_collision_action_none
  | :mav_collision_action_report
  | :mav_collision_action_ascend_or_descend
  | :mav_collision_action_move_horizontally
  | :mav_collision_action_move_perpendicular
  | :mav_collision_action_rtl
  | :mav_collision_action_hover

Possible actions an aircraft can take to avoid a collision.

Link to this type

mav_collision_src() View Source
mav_collision_src() ::
  :mav_collision_src_adsb | :mav_collision_src_mavlink_gps_global_int

Source of information about this collision.

Link to this type

mav_collision_threat_level() View Source
mav_collision_threat_level() ::
  :mav_collision_threat_level_none
  | :mav_collision_threat_level_low
  | :mav_collision_threat_level_high

Aircraft-rated danger from this threat.

Link to this type

mav_component() View Source
mav_component() ::
  :mav_comp_id_all
  | :mav_comp_id_autopilot1
  | :mav_comp_id_camera
  | :mav_comp_id_camera2
  | :mav_comp_id_camera3
  | :mav_comp_id_camera4
  | :mav_comp_id_camera5
  | :mav_comp_id_camera6
  | :mav_comp_id_servo1
  | :mav_comp_id_servo2
  | :mav_comp_id_servo3
  | :mav_comp_id_servo4
  | :mav_comp_id_servo5
  | :mav_comp_id_servo6
  | :mav_comp_id_servo7
  | :mav_comp_id_servo8
  | :mav_comp_id_servo9
  | :mav_comp_id_servo10
  | :mav_comp_id_servo11
  | :mav_comp_id_servo12
  | :mav_comp_id_servo13
  | :mav_comp_id_servo14
  | :mav_comp_id_gimbal
  | :mav_comp_id_log
  | :mav_comp_id_adsb
  | :mav_comp_id_osd
  | :mav_comp_id_peripheral
  | :mav_comp_id_qx1_gimbal
  | :mav_comp_id_flarm
  | :mav_comp_id_missionplanner
  | :mav_comp_id_pathplanner
  | :mav_comp_id_obstacle_avoidance
  | :mav_comp_id_visual_inertial_odometry
  | :mav_comp_id_imu
  | :mav_comp_id_imu_2
  | :mav_comp_id_imu_3
  | :mav_comp_id_gps
  | :mav_comp_id_gps2
  | :mav_comp_id_udp_bridge
  | :mav_comp_id_uart_bridge
  | :mav_comp_id_system_control

Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.

Link to this type

mav_data_stream() View Source
mav_data_stream() ::
  :mav_data_stream_all
  | :mav_data_stream_raw_sensors
  | :mav_data_stream_extended_status
  | :mav_data_stream_rc_channels
  | :mav_data_stream_raw_controller
  | :mav_data_stream_position
  | :mav_data_stream_extra1
  | :mav_data_stream_extra2
  | :mav_data_stream_extra3

A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.

Link to this type

mav_distance_sensor() View Source
mav_distance_sensor() ::
  :mav_distance_sensor_laser
  | :mav_distance_sensor_ultrasound
  | :mav_distance_sensor_infrared
  | :mav_distance_sensor_radar
  | :mav_distance_sensor_unknown

Enumeration of distance sensor types

Link to this type

mav_do_reposition_flags() View Source
mav_do_reposition_flags() :: :mav_do_reposition_flags_change_mode

Bitmap of options for the MAV_CMD_DO_REPOSITION

Link to this type

mav_estimator_type() View Source
mav_estimator_type() ::
  :mav_estimator_type_naive
  | :mav_estimator_type_vision
  | :mav_estimator_type_vio
  | :mav_estimator_type_gps
  | :mav_estimator_type_gps_ins

Enumeration of estimator types

Link to this type

mav_frame() View Source
mav_frame() ::
  :mav_frame_global
  | :mav_frame_local_ned
  | :mav_frame_mission
  | :mav_frame_global_relative_alt
  | :mav_frame_local_enu
  | :mav_frame_global_int
  | :mav_frame_global_relative_alt_int
  | :mav_frame_local_offset_ned
  | :mav_frame_body_ned
  | :mav_frame_body_offset_ned
  | :mav_frame_global_terrain_alt
  | :mav_frame_global_terrain_alt_int
  | :mav_frame_body_frd
  | :mav_frame_body_flu
  | :mav_frame_mocap_ned
  | :mav_frame_mocap_enu
  | :mav_frame_vision_ned
  | :mav_frame_vision_enu
  | :mav_frame_estim_ned
  | :mav_frame_estim_enu

Link to this type

mav_goto() View Source
mav_goto() ::
  :mav_goto_do_hold
  | :mav_goto_do_continue
  | :mav_goto_hold_at_current_position
  | :mav_goto_hold_at_specified_position

Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.

Link to this type

mav_landed_state() View Source
mav_landed_state() ::
  :mav_landed_state_undefined
  | :mav_landed_state_on_ground
  | :mav_landed_state_in_air
  | :mav_landed_state_takeoff
  | :mav_landed_state_landing

Enumeration of landed detector states

Link to this type

mav_mission_result() View Source
mav_mission_result() ::
  :mav_mission_accepted
  | :mav_mission_error
  | :mav_mission_unsupported_frame
  | :mav_mission_unsupported
  | :mav_mission_no_space
  | :mav_mission_invalid
  | :mav_mission_invalid_param1
  | :mav_mission_invalid_param2
  | :mav_mission_invalid_param3
  | :mav_mission_invalid_param4
  | :mav_mission_invalid_param5_x
  | :mav_mission_invalid_param6_y
  | :mav_mission_invalid_param7
  | :mav_mission_invalid_sequence
  | :mav_mission_denied
  | :mav_mission_operation_cancelled

Result of mission operation (in a MISSION_ACK message).

Link to this type

mav_mission_type() View Source
mav_mission_type() ::
  :mav_mission_type_mission
  | :mav_mission_type_fence
  | :mav_mission_type_rally
  | :mav_mission_type_all

Type of mission items being requested/sent in mission protocol.

Link to this type

mav_mode() View Source
mav_mode() ::
  :mav_mode_preflight
  | :mav_mode_stabilize_disarmed
  | :mav_mode_stabilize_armed
  | :mav_mode_manual_disarmed
  | :mav_mode_manual_armed
  | :mav_mode_guided_disarmed
  | :mav_mode_guided_armed
  | :mav_mode_auto_disarmed
  | :mav_mode_auto_armed
  | :mav_mode_test_disarmed
  | :mav_mode_test_armed

These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.

Link to this type

mav_mode_flag() View Source
mav_mode_flag() ::
  :mav_mode_flag_safety_armed
  | :mav_mode_flag_manual_input_enabled
  | :mav_mode_flag_hil_enabled
  | :mav_mode_flag_stabilize_enabled
  | :mav_mode_flag_guided_enabled
  | :mav_mode_flag_auto_enabled
  | :mav_mode_flag_test_enabled
  | :mav_mode_flag_custom_mode_enabled

These flags encode the MAV mode.

Link to this type

mav_mode_flag_decode_position() View Source
mav_mode_flag_decode_position() ::
  :mav_mode_flag_decode_position_safety
  | :mav_mode_flag_decode_position_manual
  | :mav_mode_flag_decode_position_hil
  | :mav_mode_flag_decode_position_stabilize
  | :mav_mode_flag_decode_position_guided
  | :mav_mode_flag_decode_position_auto
  | :mav_mode_flag_decode_position_test
  | :mav_mode_flag_decode_position_custom_mode

These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.

Link to this type

mav_mode_gimbal() View Source
mav_mode_gimbal() ::
  :mav_mode_gimbal_uninitialized
  | :mav_mode_gimbal_calibrating_pitch
  | :mav_mode_gimbal_calibrating_roll
  | :mav_mode_gimbal_calibrating_yaw
  | :mav_mode_gimbal_initialized
  | :mav_mode_gimbal_active
  | :mav_mode_gimbal_rate_cmd_timeout

Link to this type

mav_mount_mode() View Source
mav_mount_mode() ::
  :mav_mount_mode_retract
  | :mav_mount_mode_neutral
  | :mav_mount_mode_mavlink_targeting
  | :mav_mount_mode_rc_targeting
  | :mav_mount_mode_gps_point

Enumeration of possible mount operation modes

Link to this type

mav_param_type() View Source
mav_param_type() ::
  :mav_param_type_uint8
  | :mav_param_type_int8
  | :mav_param_type_uint16
  | :mav_param_type_int16
  | :mav_param_type_uint32
  | :mav_param_type_int32
  | :mav_param_type_uint64
  | :mav_param_type_int64
  | :mav_param_type_real32
  | :mav_param_type_real64

Specifies the datatype of a MAVLink parameter.

Link to this type

mav_power_status() View Source
mav_power_status() ::
  :mav_power_status_brick_valid
  | :mav_power_status_servo_valid
  | :mav_power_status_usb_connected
  | :mav_power_status_periph_overcurrent
  | :mav_power_status_periph_hipower_overcurrent
  | :mav_power_status_changed

Power supply status flags (bitmask)

Link to this type

mav_protocol_capability() View Source
mav_protocol_capability() ::
  :mav_protocol_capability_mission_float
  | :mav_protocol_capability_param_float
  | :mav_protocol_capability_mission_int
  | :mav_protocol_capability_command_int
  | :mav_protocol_capability_param_union
  | :mav_protocol_capability_ftp
  | :mav_protocol_capability_set_attitude_target
  | :mav_protocol_capability_set_position_target_local_ned
  | :mav_protocol_capability_set_position_target_global_int
  | :mav_protocol_capability_terrain
  | :mav_protocol_capability_set_actuator_target
  | :mav_protocol_capability_flight_termination
  | :mav_protocol_capability_compass_calibration
  | :mav_protocol_capability_mavlink2
  | :mav_protocol_capability_mission_fence
  | :mav_protocol_capability_mission_rally
  | :mav_protocol_capability_flight_information

Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.

Link to this type

mav_remote_log_data_block_commands() View Source
mav_remote_log_data_block_commands() ::
  :mav_remote_log_data_block_stop | :mav_remote_log_data_block_start

Special ACK block numbers control activation of dataflash log streaming.

Link to this type

mav_remote_log_data_block_statuses() View Source
mav_remote_log_data_block_statuses() ::
  :mav_remote_log_data_block_nack | :mav_remote_log_data_block_ack

Possible remote log data block statuses.

Link to this type

mav_result() View Source
mav_result() ::
  :mav_result_accepted
  | :mav_result_temporarily_rejected
  | :mav_result_denied
  | :mav_result_unsupported
  | :mav_result_failed

result from a mavlink command

Link to this type

mav_roi() View Source
mav_roi() ::
  :mav_roi_none
  | :mav_roi_wpnext
  | :mav_roi_wpindex
  | :mav_roi_location
  | :mav_roi_target

THIS INTERFACE IS DEPRECATED AS OF JANUARY 2018. Please use MAVCMD_DO_SET_ROI* messages instead. The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI).

Link to this type

mav_sensor_orientation() View Source
mav_sensor_orientation() ::
  :mav_sensor_rotation_none
  | :mav_sensor_rotation_yaw_45
  | :mav_sensor_rotation_yaw_90
  | :mav_sensor_rotation_yaw_135
  | :mav_sensor_rotation_yaw_180
  | :mav_sensor_rotation_yaw_225
  | :mav_sensor_rotation_yaw_270
  | :mav_sensor_rotation_yaw_315
  | :mav_sensor_rotation_roll_180
  | :mav_sensor_rotation_roll_180_yaw_45
  | :mav_sensor_rotation_roll_180_yaw_90
  | :mav_sensor_rotation_roll_180_yaw_135
  | :mav_sensor_rotation_pitch_180
  | :mav_sensor_rotation_roll_180_yaw_225
  | :mav_sensor_rotation_roll_180_yaw_270
  | :mav_sensor_rotation_roll_180_yaw_315
  | :mav_sensor_rotation_roll_90
  | :mav_sensor_rotation_roll_90_yaw_45
  | :mav_sensor_rotation_roll_90_yaw_90
  | :mav_sensor_rotation_roll_90_yaw_135
  | :mav_sensor_rotation_roll_270
  | :mav_sensor_rotation_roll_270_yaw_45
  | :mav_sensor_rotation_roll_270_yaw_90
  | :mav_sensor_rotation_roll_270_yaw_135
  | :mav_sensor_rotation_pitch_90
  | :mav_sensor_rotation_pitch_270
  | :mav_sensor_rotation_pitch_180_yaw_90
  | :mav_sensor_rotation_pitch_180_yaw_270
  | :mav_sensor_rotation_roll_90_pitch_90
  | :mav_sensor_rotation_roll_180_pitch_90
  | :mav_sensor_rotation_roll_270_pitch_90
  | :mav_sensor_rotation_roll_90_pitch_180
  | :mav_sensor_rotation_roll_270_pitch_180
  | :mav_sensor_rotation_roll_90_pitch_270
  | :mav_sensor_rotation_roll_180_pitch_270
  | :mav_sensor_rotation_roll_270_pitch_270
  | :mav_sensor_rotation_roll_90_pitch_180_yaw_90
  | :mav_sensor_rotation_roll_90_yaw_270
  | :mav_sensor_rotation_roll_90_pitch_68_yaw_293
  | :mav_sensor_rotation_pitch_315
  | :mav_sensor_rotation_roll_90_pitch_315
  | :mav_sensor_rotation_custom

Enumeration of sensor orientation, according to its rotations

Link to this type

mav_severity() View Source
mav_severity() ::
  :mav_severity_emergency
  | :mav_severity_alert
  | :mav_severity_critical
  | :mav_severity_error
  | :mav_severity_warning
  | :mav_severity_notice
  | :mav_severity_info
  | :mav_severity_debug

Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.

Link to this type

mav_state() View Source
mav_state() ::
  :mav_state_uninit
  | :mav_state_boot
  | :mav_state_calibrating
  | :mav_state_standby
  | :mav_state_active
  | :mav_state_critical
  | :mav_state_emergency
  | :mav_state_poweroff
  | :mav_state_flight_termination

Link to this type

mav_sys_status_sensor() View Source
mav_sys_status_sensor() ::
  :mav_sys_status_sensor_3d_gyro
  | :mav_sys_status_sensor_3d_accel
  | :mav_sys_status_sensor_3d_mag
  | :mav_sys_status_sensor_absolute_pressure
  | :mav_sys_status_sensor_differential_pressure
  | :mav_sys_status_sensor_gps
  | :mav_sys_status_sensor_optical_flow
  | :mav_sys_status_sensor_vision_position
  | :mav_sys_status_sensor_laser_position
  | :mav_sys_status_sensor_external_ground_truth
  | :mav_sys_status_sensor_angular_rate_control
  | :mav_sys_status_sensor_attitude_stabilization
  | :mav_sys_status_sensor_yaw_position
  | :mav_sys_status_sensor_z_altitude_control
  | :mav_sys_status_sensor_xy_position_control
  | :mav_sys_status_sensor_motor_outputs
  | :mav_sys_status_sensor_rc_receiver
  | :mav_sys_status_sensor_3d_gyro2
  | :mav_sys_status_sensor_3d_accel2
  | :mav_sys_status_sensor_3d_mag2
  | :mav_sys_status_geofence
  | :mav_sys_status_ahrs
  | :mav_sys_status_terrain
  | :mav_sys_status_reverse_motor
  | :mav_sys_status_logging
  | :mav_sys_status_sensor_battery
  | :mav_sys_status_sensor_proximity
  | :mav_sys_status_sensor_satcom

These encode the sensors whose status is sent as part of the SYS_STATUS message.

Link to this type

mav_type() View Source
mav_type() ::
  :mav_type_generic
  | :mav_type_fixed_wing
  | :mav_type_quadrotor
  | :mav_type_coaxial
  | :mav_type_helicopter
  | :mav_type_antenna_tracker
  | :mav_type_gcs
  | :mav_type_airship
  | :mav_type_free_balloon
  | :mav_type_rocket
  | :mav_type_ground_rover
  | :mav_type_surface_boat
  | :mav_type_submarine
  | :mav_type_hexarotor
  | :mav_type_octorotor
  | :mav_type_tricopter
  | :mav_type_flapping_wing
  | :mav_type_kite
  | :mav_type_onboard_controller
  | :mav_type_vtol_duorotor
  | :mav_type_vtol_quadrotor
  | :mav_type_vtol_tiltrotor
  | :mav_type_vtol_reserved2
  | :mav_type_vtol_reserved3
  | :mav_type_vtol_reserved4
  | :mav_type_vtol_reserved5
  | :mav_type_gimbal
  | :mav_type_adsb
  | :mav_type_parafoil
  | :mav_type_dodecarotor
  | :mav_type_camera
  | :mav_type_charging_station
  | :mav_type_flarm

MAVLINK system type. All components in a system should report this type in their HEARTBEAT.

Link to this type

mav_vtol_state() View Source
mav_vtol_state() ::
  :mav_vtol_state_undefined
  | :mav_vtol_state_transition_to_fw
  | :mav_vtol_state_transition_to_mc
  | :mav_vtol_state_mc
  | :mav_vtol_state_fw

Enumeration of VTOL states

Link to this type

message() View Source
message() ::
  APM.Message.Heartbeat
  | APM.Message.SysStatus
  | APM.Message.SystemTime
  | APM.Message.Ping
  | APM.Message.ChangeOperatorControl
  | APM.Message.ChangeOperatorControlAck
  | APM.Message.AuthKey
  | APM.Message.SetMode
  | APM.Message.ParamRequestRead
  | APM.Message.ParamRequestList
  | APM.Message.ParamValue
  | APM.Message.ParamSet
  | APM.Message.GpsRawInt
  | APM.Message.GpsStatus
  | APM.Message.ScaledImu
  | APM.Message.RawImu
  | APM.Message.RawPressure
  | APM.Message.ScaledPressure
  | APM.Message.Attitude
  | APM.Message.AttitudeQuaternion
  | APM.Message.LocalPositionNed
  | APM.Message.GlobalPositionInt
  | APM.Message.RcChannelsScaled
  | APM.Message.RcChannelsRaw
  | APM.Message.ServoOutputRaw
  | APM.Message.MissionRequestPartialList
  | APM.Message.MissionWritePartialList
  | APM.Message.MissionItem
  | APM.Message.MissionRequest
  | APM.Message.MissionSetCurrent
  | APM.Message.MissionCurrent
  | APM.Message.MissionRequestList
  | APM.Message.MissionCount
  | APM.Message.MissionClearAll
  | APM.Message.MissionItemReached
  | APM.Message.MissionAck
  | APM.Message.SetGpsGlobalOrigin
  | APM.Message.GpsGlobalOrigin
  | APM.Message.ParamMapRc
  | APM.Message.MissionRequestInt
  | APM.Message.SafetySetAllowedArea
  | APM.Message.SafetyAllowedArea
  | APM.Message.AttitudeQuaternionCov
  | APM.Message.NavControllerOutput
  | APM.Message.GlobalPositionIntCov
  | APM.Message.LocalPositionNedCov
  | APM.Message.RcChannels
  | APM.Message.RequestDataStream
  | APM.Message.DataStream
  | APM.Message.ManualControl
  | APM.Message.RcChannelsOverride
  | APM.Message.MissionItemInt
  | APM.Message.VfrHud
  | APM.Message.CommandInt
  | APM.Message.CommandLong
  | APM.Message.CommandAck
  | APM.Message.ManualSetpoint
  | APM.Message.SetAttitudeTarget
  | APM.Message.AttitudeTarget
  | APM.Message.SetPositionTargetLocalNed
  | APM.Message.PositionTargetLocalNed
  | APM.Message.SetPositionTargetGlobalInt
  | APM.Message.PositionTargetGlobalInt
  | APM.Message.LocalPositionNedSystemGlobalOffset
  | APM.Message.HilState
  | APM.Message.HilControls
  | APM.Message.HilRcInputsRaw
  | APM.Message.HilActuatorControls
  | APM.Message.OpticalFlow
  | APM.Message.GlobalVisionPositionEstimate
  | APM.Message.VisionPositionEstimate
  | APM.Message.VisionSpeedEstimate
  | APM.Message.ViconPositionEstimate
  | APM.Message.HighresImu
  | APM.Message.OpticalFlowRad
  | APM.Message.HilSensor
  | APM.Message.RadioStatus
  | APM.Message.FileTransferProtocol
  | APM.Message.Timesync
  | APM.Message.CameraTrigger
  | APM.Message.HilGps
  | APM.Message.HilOpticalFlow
  | APM.Message.HilStateQuaternion
  | APM.Message.ScaledImu2
  | APM.Message.LogRequestList
  | APM.Message.LogEntry
  | APM.Message.LogRequestData
  | APM.Message.LogData
  | APM.Message.LogErase
  | APM.Message.LogRequestEnd
  | APM.Message.GpsInjectData
  | APM.Message.Gps2Raw
  | APM.Message.PowerStatus
  | APM.Message.SerialControl
  | APM.Message.GpsRtk
  | APM.Message.Gps2Rtk
  | APM.Message.ScaledImu3
  | APM.Message.DataTransmissionHandshake
  | APM.Message.EncapsulatedData
  | APM.Message.DistanceSensor
  | APM.Message.TerrainRequest
  | APM.Message.TerrainData
  | APM.Message.TerrainCheck
  | APM.Message.TerrainReport
  | APM.Message.ScaledPressure2
  | APM.Message.AttPosMocap
  | APM.Message.SetActuatorControlTarget
  | APM.Message.ActuatorControlTarget
  | APM.Message.Altitude
  | APM.Message.ResourceRequest
  | APM.Message.ScaledPressure3
  | APM.Message.FollowTarget
  | APM.Message.ControlSystemState
  | APM.Message.BatteryStatus
  | APM.Message.AutopilotVersion
  | APM.Message.LandingTarget
  | APM.Message.SensorOffsets
  | APM.Message.SetMagOffsets
  | APM.Message.Meminfo
  | APM.Message.ApAdc
  | APM.Message.DigicamConfigure
  | APM.Message.DigicamControl
  | APM.Message.MountConfigure
  | APM.Message.MountControl
  | APM.Message.MountStatus
  | APM.Message.FencePoint
  | APM.Message.FenceFetchPoint
  | APM.Message.FenceStatus
  | APM.Message.Ahrs
  | APM.Message.Simstate
  | APM.Message.Hwstatus
  | APM.Message.Radio
  | APM.Message.LimitsStatus
  | APM.Message.Wind
  | APM.Message.Data16
  | APM.Message.Data32
  | APM.Message.Data64
  | APM.Message.Data96
  | APM.Message.Rangefinder
  | APM.Message.AirspeedAutocal
  | APM.Message.RallyPoint
  | APM.Message.RallyFetchPoint
  | APM.Message.CompassmotStatus
  | APM.Message.Ahrs2
  | APM.Message.CameraStatus
  | APM.Message.CameraFeedback
  | APM.Message.Battery2
  | APM.Message.Ahrs3
  | APM.Message.AutopilotVersionRequest
  | APM.Message.RemoteLogDataBlock
  | APM.Message.RemoteLogBlockStatus
  | APM.Message.LedControl
  | APM.Message.MagCalProgress
  | APM.Message.MagCalReport
  | APM.Message.EkfStatusReport
  | APM.Message.PidTuning
  | APM.Message.Deepstall
  | APM.Message.GimbalReport
  | APM.Message.GimbalControl
  | APM.Message.GimbalTorqueCmdReport
  | APM.Message.GoproHeartbeat
  | APM.Message.GoproGetRequest
  | APM.Message.GoproGetResponse
  | APM.Message.GoproSetRequest
  | APM.Message.GoproSetResponse
  | APM.Message.Rpm
  | APM.Message.EstimatorStatus
  | APM.Message.WindCov
  | APM.Message.GpsInput
  | APM.Message.GpsRtcmData
  | APM.Message.HighLatency
  | APM.Message.Vibration
  | APM.Message.HomePosition
  | APM.Message.SetHomePosition
  | APM.Message.MessageInterval
  | APM.Message.ExtendedSysState
  | APM.Message.AdsbVehicle
  | APM.Message.Collision
  | APM.Message.V2Extension
  | APM.Message.MemoryVect
  | APM.Message.DebugVect
  | APM.Message.NamedValueFloat
  | APM.Message.NamedValueInt
  | APM.Message.Statustext
  | APM.Message.Debug
  | APM.Message.SetupSigning
  | APM.Message.ButtonChange
  | APM.Message.PlayTune
  | APM.Message.CameraInformation
  | APM.Message.CameraSettings
  | APM.Message.StorageInformation
  | APM.Message.CameraCaptureStatus
  | APM.Message.CameraImageCaptured
  | APM.Message.FlightInformation
  | APM.Message.MountOrientation
  | APM.Message.LoggingData
  | APM.Message.LoggingDataAcked
  | APM.Message.LoggingAck
  | APM.Message.WifiConfigAp
  | APM.Message.UavcanNodeStatus
  | APM.Message.UavcanNodeInfo
  | APM.Message.ObstacleDistance
  | APM.Message.Odometry
  | APM.Message.DebugFloatArray
  | APM.Message.StatustextLong
  | APM.Message.WheelDistance
  | APM.Message.UavionixAdsbOutCfg
  | APM.Message.UavionixAdsbOutDynamic
  | APM.Message.UavionixAdsbTransceiverHealthReport
  | APM.Message.DeviceOpRead
  | APM.Message.DeviceOpReadReply
  | APM.Message.DeviceOpWrite
  | APM.Message.DeviceOpWriteReply
  | APM.Message.AdapTuning
  | APM.Message.VisionPositionDelta
  | APM.Message.AoaSsa
  | APM.Message.EscTelemetry1To4
  | APM.Message.EscTelemetry5To8
  | APM.Message.EscTelemetry9To12
  | APM.Message.IcarousHeartbeat
  | APM.Message.IcarousKinematicBands

A MAVLink message

Link to this type

motor_test_order() View Source
motor_test_order() ::
  :motor_test_order_default
  | :motor_test_order_sequence
  | :motor_test_order_board

Link to this type

motor_test_throttle_type() View Source
motor_test_throttle_type() ::
  :motor_test_throttle_percent
  | :motor_test_throttle_pwm
  | :motor_test_throttle_pilot
  | :motor_test_compass_cal

Link to this type

parachute_action() View Source
parachute_action() ::
  :parachute_disable | :parachute_enable | :parachute_release

Link to this type

pid_tuning_axis() View Source
pid_tuning_axis() ::
  :pid_tuning_roll
  | :pid_tuning_pitch
  | :pid_tuning_yaw
  | :pid_tuning_accz
  | :pid_tuning_steer
  | :pid_tuning_landing

Link to this type

plane_mode() View Source
plane_mode() ::
  :plane_mode_manual
  | :plane_mode_circle
  | :plane_mode_stabilize
  | :plane_mode_training
  | :plane_mode_acro
  | :plane_mode_fly_by_wire_a
  | :plane_mode_fly_by_wire_b
  | :plane_mode_cruise
  | :plane_mode_autotune
  | :plane_mode_auto
  | :plane_mode_rtl
  | :plane_mode_loiter
  | :plane_mode_avoid_adsb
  | :plane_mode_guided
  | :plane_mode_initializing
  | :plane_mode_qstabilize
  | :plane_mode_qhover
  | :plane_mode_qloiter
  | :plane_mode_qland
  | :plane_mode_qrtl
  | :plane_mode_qautotune

A mapping of plane flight modes for custom_mode field of heartbeat.

Link to this type

position_target_typemask() View Source
position_target_typemask() ::
  :position_target_typemask_x_ignore
  | :position_target_typemask_y_ignore
  | :position_target_typemask_z_ignore
  | :position_target_typemask_vx_ignore
  | :position_target_typemask_vy_ignore
  | :position_target_typemask_vz_ignore
  | :position_target_typemask_ax_ignore
  | :position_target_typemask_ay_ignore
  | :position_target_typemask_az_ignore
  | :position_target_typemask_force_set
  | :position_target_typemask_yaw_ignore
  | :position_target_typemask_yaw_rate_ignore

Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration.

Link to this type

precision_land_mode() View Source
precision_land_mode() ::
  :precision_land_mode_disabled
  | :precision_land_mode_opportunistic
  | :precision_land_mode_required

Precision land modes (used in MAV_CMD_NAV_LAND).

Link to this type

rally_flags() View Source
rally_flags() :: :favorable_wind | :land_immediately

Flags in RALLY_POINT message.

Link to this type

rc_type() View Source
rc_type() :: :rc_type_spektrum_dsm2 | :rc_type_spektrum_dsmx

RC type

Link to this type

rover_mode() View Source
rover_mode() ::
  :rover_mode_manual
  | :rover_mode_acro
  | :rover_mode_steering
  | :rover_mode_hold
  | :rover_mode_loiter
  | :rover_mode_auto
  | :rover_mode_rtl
  | :rover_mode_smart_rtl
  | :rover_mode_guided
  | :rover_mode_initializing

A mapping of rover flight modes for custom_mode field of heartbeat.

Link to this type

rtk_baseline_coordinate_system() View Source
rtk_baseline_coordinate_system() ::
  :rtk_baseline_coordinate_system_ecef | :rtk_baseline_coordinate_system_ned

RTK GPS baseline coordinate system, used for RTK corrections

Link to this type

serial_control_dev() View Source
serial_control_dev() ::
  :serial_control_dev_telem1
  | :serial_control_dev_telem2
  | :serial_control_dev_gps1
  | :serial_control_dev_gps2
  | :serial_control_dev_shell

SERIAL_CONTROL device types

Link to this type

serial_control_flag() View Source
serial_control_flag() ::
  :serial_control_flag_reply
  | :serial_control_flag_respond
  | :serial_control_flag_exclusive
  | :serial_control_flag_blocking
  | :serial_control_flag_multi

SERIAL_CONTROL flags (bitmask)

Link to this type

storage_status() View Source
storage_status() ::
  :storage_status_empty
  | :storage_status_unformatted
  | :storage_status_ready
  | :storage_status_not_supported

Flags to indicate the status of camera storage.

Link to this type

sub_mode() View Source
sub_mode() ::
  :sub_mode_stabilize
  | :sub_mode_acro
  | :sub_mode_alt_hold
  | :sub_mode_auto
  | :sub_mode_guided
  | :sub_mode_circle
  | :sub_mode_surface
  | :sub_mode_poshold
  | :sub_mode_manual

A mapping of sub flight modes for custom_mode field of heartbeat.

Link to this type

tracker_mode() View Source
tracker_mode() ::
  :tracker_mode_manual
  | :tracker_mode_stop
  | :tracker_mode_scan
  | :tracker_mode_servo_test
  | :tracker_mode_auto
  | :tracker_mode_initializing

A mapping of antenna tracker flight modes for custom_mode field of heartbeat.

Link to this type

uavcan_node_health() View Source
uavcan_node_health() ::
  :uavcan_node_health_ok
  | :uavcan_node_health_warning
  | :uavcan_node_health_error
  | :uavcan_node_health_critical

Generalized UAVCAN node health

Link to this type

uavcan_node_mode() View Source
uavcan_node_mode() ::
  :uavcan_node_mode_operational
  | :uavcan_node_mode_initialization
  | :uavcan_node_mode_maintenance
  | :uavcan_node_mode_software_update
  | :uavcan_node_mode_offline

Generalized UAVCAN node mode

Link to this type

uavionix_adsb_emergency_status() View Source
uavionix_adsb_emergency_status() ::
  :uavionix_adsb_out_no_emergency
  | :uavionix_adsb_out_general_emergency
  | :uavionix_adsb_out_lifeguard_emergency
  | :uavionix_adsb_out_minimum_fuel_emergency
  | :uavionix_adsb_out_no_comm_emergency
  | :uavionix_adsb_out_unlawful_interferance_emergency
  | :uavionix_adsb_out_downed_aircraft_emergency
  | :uavionix_adsb_out_reserved

Emergency status encoding

Link to this type

uavionix_adsb_out_cfg_aircraft_size() View Source
uavionix_adsb_out_cfg_aircraft_size() ::
  :uavionix_adsb_out_cfg_aircraft_size_no_data
  | :uavionix_adsb_out_cfg_aircraft_size_l15m_w23m
  | :uavionix_adsb_out_cfg_aircraft_size_l25m_w28p5m
  | :uavionix_adsb_out_cfg_aircraft_size_l25_34m
  | :uavionix_adsb_out_cfg_aircraft_size_l35_33m
  | :uavionix_adsb_out_cfg_aircraft_size_l35_38m
  | :uavionix_adsb_out_cfg_aircraft_size_l45_39p5m
  | :uavionix_adsb_out_cfg_aircraft_size_l45_45m
  | :uavionix_adsb_out_cfg_aircraft_size_l55_45m
  | :uavionix_adsb_out_cfg_aircraft_size_l55_52m
  | :uavionix_adsb_out_cfg_aircraft_size_l65_59p5m
  | :uavionix_adsb_out_cfg_aircraft_size_l65_67m
  | :uavionix_adsb_out_cfg_aircraft_size_l75_w72p5m
  | :uavionix_adsb_out_cfg_aircraft_size_l75_w80m
  | :uavionix_adsb_out_cfg_aircraft_size_l85_w80m
  | :uavionix_adsb_out_cfg_aircraft_size_l85_w90m

Definitions for aircraft size

Link to this type

uavionix_adsb_out_cfg_gps_offset_lat() View Source
uavionix_adsb_out_cfg_gps_offset_lat() ::
  :uavionix_adsb_out_cfg_gps_offset_lat_no_data
  | :uavionix_adsb_out_cfg_gps_offset_lat_left_2m
  | :uavionix_adsb_out_cfg_gps_offset_lat_left_4m
  | :uavionix_adsb_out_cfg_gps_offset_lat_left_6m
  | :uavionix_adsb_out_cfg_gps_offset_lat_right_0m
  | :uavionix_adsb_out_cfg_gps_offset_lat_right_2m
  | :uavionix_adsb_out_cfg_gps_offset_lat_right_4m
  | :uavionix_adsb_out_cfg_gps_offset_lat_right_6m

GPS lataral offset encoding

Link to this type

uavionix_adsb_out_cfg_gps_offset_lon() View Source
uavionix_adsb_out_cfg_gps_offset_lon() ::
  :uavionix_adsb_out_cfg_gps_offset_lon_no_data
  | :uavionix_adsb_out_cfg_gps_offset_lon_applied_by_sensor

GPS longitudinal offset encoding

Link to this type

uavionix_adsb_out_dynamic_gps_fix() View Source
uavionix_adsb_out_dynamic_gps_fix() ::
  :uavionix_adsb_out_dynamic_gps_fix_none_0
  | :uavionix_adsb_out_dynamic_gps_fix_none_1
  | :uavionix_adsb_out_dynamic_gps_fix_2d
  | :uavionix_adsb_out_dynamic_gps_fix_3d
  | :uavionix_adsb_out_dynamic_gps_fix_dgps
  | :uavionix_adsb_out_dynamic_gps_fix_rtk

Status for ADS-B transponder dynamic input

Link to this type

uavionix_adsb_out_dynamic_state() View Source
uavionix_adsb_out_dynamic_state() ::
  :uavionix_adsb_out_dynamic_state_intent_change
  | :uavionix_adsb_out_dynamic_state_autopilot_enabled
  | :uavionix_adsb_out_dynamic_state_nicbaro_crosschecked
  | :uavionix_adsb_out_dynamic_state_on_ground
  | :uavionix_adsb_out_dynamic_state_ident

State flags for ADS-B transponder dynamic report

Link to this type

uavionix_adsb_out_rf_select() View Source
uavionix_adsb_out_rf_select() ::
  :uavionix_adsb_out_rf_select_standby
  | :uavionix_adsb_out_rf_select_rx_enabled
  | :uavionix_adsb_out_rf_select_tx_enabled

Transceiver RF control flags for ADS-B transponder dynamic reports

Link to this type

uavionix_adsb_rf_health() View Source
uavionix_adsb_rf_health() ::
  :uavionix_adsb_rf_health_initializing
  | :uavionix_adsb_rf_health_ok
  | :uavionix_adsb_rf_health_fail_tx
  | :uavionix_adsb_rf_health_fail_rx

Status flags for ADS-B transponder dynamic output

Link to this type

vtol_transition_heading() View Source
vtol_transition_heading() ::
  :vtol_transition_heading_vehicle_default
  | :vtol_transition_heading_next_waypoint
  | :vtol_transition_heading_takeoff
  | :vtol_transition_heading_specified
  | :vtol_transition_heading_any

Direction of VTOL transition

Link to this type

winch_actions() View Source
winch_actions() ::
  :winch_relaxed | :winch_relative_length_control | :winch_rate_control

Winch actions.