View Source Common.Types (xmavlink_util v0.4.0)

Link to this section Summary

Types

Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.

Actuator output function. Values greater or equal to 1000 are autopilot-specific.

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

These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid.

Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored.

Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.

Camera capability flags (Bitmap)

Camera Modes.

Camera tracking modes

Camera tracking status flags

Camera tracking target data (shows where tracked target is within image)

Zoom types for MAV_CMD_SET_CAMERA_ZOOM

Possible responses from a CELLULAR_CONFIG message.

These flags are used to diagnose the failure state of CELLULAR_STATUS

Cellular network radio type

These flags encode the cellular network status

Supported component metadata types. These are used in the general metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages.

An atom representing a MAVLink enumeration type

An atom representing a MAVLink enumeration type value

Indicates the ESC connection type.

Flags to report ESC failures.

Flags in ESTIMATOR_STATUS message

List of possible failure type to inject.

List of possible units where failures can be injected.

Actions following geofence breach.

Actions being taken to mitigate/prevent fence breach

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.

Gimbal device (low level) capability flags (bitmap).

Gimbal device (low level) error flags (bitmap, 0 means no error)

Flags for gimbal device (lower level) operation.

Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags.

Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.

Type of GPS fix

Gripper actions.

Flags in the HIGHRES_IMU message indicate which fields have updated since the last message

Flags in the HIL_SENSOR message indicate which fields have updated since the last message

Flags to report failure cases over the high latency telemtry.

Type of landing target

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

Enumeration for battery charge states.

Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set.

Enumeration of battery functions

Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight.

Enumeration of battery types

Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries

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

Flags for CURRENT_EVENT_SEQUENCE.

Reason for an event error response.

Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - 'GLOBAL': Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with 'GLOBAL': - 'RELATIVE_ALT': Altitude is relative to the vehicle home position rather than MSL. - 'TERRAIN_ALT': Altitude is relative to ground level rather than MSL. - 'INT': Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - 'LOCAL': Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator ('EKF'). - 'BODY': Origin of local frame travels with the vehicle. NOTE, 'BODY' does NOT indicate alignment of frame axis with vehicle attitude. - 'OFFSET': Deprecated synonym for 'BODY' (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).

Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).

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. This message is used by obsolete/deprecated gimbal messages.

Specifies the datatype of a MAVLink extended parameter.

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.

Result from a MAVLink command (MAV_CMD)

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.

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

MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).

Enumeration of VTOL states

Winch status flags used in WINCH_STATUS

A MAVLink message

States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles.

Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST.

Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST.

Yaw behaviour during orbit flight.

Parachute actions. Trigger release and enable/disable auto-release.

Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).

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).

Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

RC type

RTK GPS baseline coordinate system, used for RTK corrections

SERIAL_CONTROL device types

SERIAL_CONTROL flags (bitmask)

Focus types for MAV_CMD_SET_CAMERA_FOCUS

Flags to indicate the status of camera storage.

Flags to indicate the type of storage.

Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).

Tune formats (used for vehicle buzzer/tone generation).

Generalized UAVCAN node health

Generalized UAVCAN node mode

Flags for the global position report.

Airborne status of UAS.

Stream status flags (Bitmap)

Video stream types

Direction of VTOL transition

Possible responses from a WIFI_CONFIG_AP message.

Winch actions.

Link to this section Types

Link to this type

actuator_configuration()

View Source
@type actuator_configuration() ::
  :actuator_configuration_none
  | :actuator_configuration_beep
  | :actuator_configuration_3d_mode_on
  | :actuator_configuration_3d_mode_off
  | :actuator_configuration_spin_direction1
  | :actuator_configuration_spin_direction2

Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.

Link to this type

actuator_output_function()

View Source
@type actuator_output_function() ::
  :actuator_output_function_none
  | :actuator_output_function_motor1
  | :actuator_output_function_motor2
  | :actuator_output_function_motor3
  | :actuator_output_function_motor4
  | :actuator_output_function_motor5
  | :actuator_output_function_motor6
  | :actuator_output_function_motor7
  | :actuator_output_function_motor8
  | :actuator_output_function_motor9
  | :actuator_output_function_motor10
  | :actuator_output_function_motor11
  | :actuator_output_function_motor12
  | :actuator_output_function_motor13
  | :actuator_output_function_motor14
  | :actuator_output_function_motor15
  | :actuator_output_function_motor16
  | :actuator_output_function_servo1
  | :actuator_output_function_servo2
  | :actuator_output_function_servo3
  | :actuator_output_function_servo4
  | :actuator_output_function_servo5
  | :actuator_output_function_servo6
  | :actuator_output_function_servo7
  | :actuator_output_function_servo8
  | :actuator_output_function_servo9
  | :actuator_output_function_servo10
  | :actuator_output_function_servo11
  | :actuator_output_function_servo12
  | :actuator_output_function_servo13
  | :actuator_output_function_servo14
  | :actuator_output_function_servo15
  | :actuator_output_function_servo16

Actuator output function. Values greater or equal to 1000 are autopilot-specific.

@type adsb_altitude_type() ::
  :adsb_altitude_type_pressure_qnh | :adsb_altitude_type_geometric

Enumeration of the ADSB altimeter types

@type 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

@type 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
  | :adsb_flags_vertical_velocity_valid
  | :adsb_flags_baro_valid
  | :adsb_flags_source_uat

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

@type ais_flags() ::
  :ais_flags_position_accuracy
  | :ais_flags_valid_cog
  | :ais_flags_valid_velocity
  | :ais_flags_high_velocity
  | :ais_flags_valid_turn_rate
  | :ais_flags_turn_rate_sign_only
  | :ais_flags_valid_dimensions
  | :ais_flags_large_bow_dimension
  | :ais_flags_large_stern_dimension
  | :ais_flags_large_port_dimension
  | :ais_flags_large_starboard_dimension
  | :ais_flags_valid_callsign
  | :ais_flags_valid_name

These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid.

@type ais_nav_status() ::
  :under_way
  | :ais_nav_anchored
  | :ais_nav_un_commanded
  | :ais_nav_restricted_manoeuverability
  | :ais_nav_draught_constrained
  | :ais_nav_moored
  | :ais_nav_aground
  | :ais_nav_fishing
  | :ais_nav_sailing
  | :ais_nav_reserved_hsc
  | :ais_nav_reserved_wig
  | :ais_nav_reserved_1
  | :ais_nav_reserved_2
  | :ais_nav_reserved_3
  | :ais_nav_ais_sart
  | :ais_nav_unknown

Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

@type ais_type() ::
  :ais_type_unknown
  | :ais_type_reserved_1
  | :ais_type_reserved_2
  | :ais_type_reserved_3
  | :ais_type_reserved_4
  | :ais_type_reserved_5
  | :ais_type_reserved_6
  | :ais_type_reserved_7
  | :ais_type_reserved_8
  | :ais_type_reserved_9
  | :ais_type_reserved_10
  | :ais_type_reserved_11
  | :ais_type_reserved_12
  | :ais_type_reserved_13
  | :ais_type_reserved_14
  | :ais_type_reserved_15
  | :ais_type_reserved_16
  | :ais_type_reserved_17
  | :ais_type_reserved_18
  | :ais_type_reserved_19
  | :ais_type_wig
  | :ais_type_wig_hazardous_a
  | :ais_type_wig_hazardous_b
  | :ais_type_wig_hazardous_c
  | :ais_type_wig_hazardous_d
  | :ais_type_wig_reserved_1
  | :ais_type_wig_reserved_2
  | :ais_type_wig_reserved_3
  | :ais_type_wig_reserved_4
  | :ais_type_wig_reserved_5
  | :ais_type_fishing
  | :ais_type_towing
  | :ais_type_towing_large
  | :ais_type_dredging
  | :ais_type_diving
  | :ais_type_military
  | :ais_type_sailing
  | :ais_type_pleasure
  | :ais_type_reserved_20
  | :ais_type_reserved_21
  | :ais_type_hsc
  | :ais_type_hsc_hazardous_a
  | :ais_type_hsc_hazardous_b
  | :ais_type_hsc_hazardous_c
  | :ais_type_hsc_hazardous_d
  | :ais_type_hsc_reserved_1
  | :ais_type_hsc_reserved_2
  | :ais_type_hsc_reserved_3
  | :ais_type_hsc_reserved_4
  | :ais_type_hsc_unknown
  | :ais_type_pilot
  | :ais_type_sar
  | :ais_type_tug
  | :ais_type_port_tender
  | :ais_type_anti_pollution
  | :ais_type_law_enforcement
  | :ais_type_spare_local_1
  | :ais_type_spare_local_2
  | :ais_type_medical_transport
  | :ais_type_nonecombatant
  | :ais_type_passenger
  | :ais_type_passenger_hazardous_a
  | :ais_type_passenger_hazardous_b
  | :ais_type_ais_type_passenger_hazardous_c
  | :ais_type_passenger_hazardous_d
  | :ais_type_passenger_reserved_1
  | :ais_type_passenger_reserved_2
  | :ais_type_passenger_reserved_3
  | :ais_type_ais_type_passenger_reserved_4
  | :ais_type_passenger_unknown
  | :ais_type_cargo
  | :ais_type_cargo_hazardous_a
  | :ais_type_cargo_hazardous_b
  | :ais_type_cargo_hazardous_c
  | :ais_type_cargo_hazardous_d
  | :ais_type_cargo_reserved_1
  | :ais_type_cargo_reserved_2
  | :ais_type_cargo_reserved_3
  | :ais_type_cargo_reserved_4
  | :ais_type_cargo_unknown
  | :ais_type_tanker
  | :ais_type_tanker_hazardous_a
  | :ais_type_tanker_hazardous_b
  | :ais_type_tanker_hazardous_c
  | :ais_type_tanker_hazardous_d
  | :ais_type_tanker_reserved_1
  | :ais_type_tanker_reserved_2
  | :ais_type_tanker_reserved_3
  | :ais_type_tanker_reserved_4
  | :ais_type_tanker_unknown
  | :ais_type_other
  | :ais_type_other_hazardous_a
  | :ais_type_other_hazardous_b
  | :ais_type_other_hazardous_c
  | :ais_type_other_hazardous_d
  | :ais_type_other_reserved_1
  | :ais_type_other_reserved_2
  | :ais_type_other_reserved_3
  | :ais_type_other_reserved_4
  | :ais_type_other_unknown

Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

Link to this type

attitude_target_typemask()

View Source
@type attitude_target_typemask() ::
  :attitude_target_typemask_body_roll_rate_ignore
  | :attitude_target_typemask_body_pitch_rate_ignore
  | :attitude_target_typemask_body_yaw_rate_ignore
  | :attitude_target_typemask_thrust_body_set
  | :attitude_target_typemask_throttle_ignore
  | :attitude_target_typemask_attitude_ignore

Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored.

@type autotune_axis() ::
  :autotune_axis_default
  | :autotune_axis_roll
  | :autotune_axis_pitch
  | :autotune_axis_yaw

Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.

@type 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_cap_flags_has_tracking_point
  | :camera_cap_flags_has_tracking_rectangle
  | :camera_cap_flags_has_tracking_geo_status

Camera capability flags (Bitmap)

@type camera_mode() ::
  :camera_mode_image | :camera_mode_video | :camera_mode_image_survey

Camera Modes.

Link to this type

camera_tracking_mode()

View Source
@type camera_tracking_mode() ::
  :camera_tracking_mode_none
  | :camera_tracking_mode_point
  | :camera_tracking_mode_rectangle

Camera tracking modes

Link to this type

camera_tracking_status_flags()

View Source
@type camera_tracking_status_flags() ::
  :camera_tracking_status_flags_idle
  | :camera_tracking_status_flags_active
  | :camera_tracking_status_flags_error

Camera tracking status flags

Link to this type

camera_tracking_target_data()

View Source
@type camera_tracking_target_data() ::
  :camera_tracking_target_data_none
  | :camera_tracking_target_data_embedded
  | :camera_tracking_target_data_rendered
  | :camera_tracking_target_data_in_status

Camera tracking target data (shows where tracked target is within image)

@type camera_zoom_type() ::
  :zoom_type_step
  | :zoom_type_continuous
  | :zoom_type_range
  | :zoom_type_focal_length

Zoom types for MAV_CMD_SET_CAMERA_ZOOM

@type can_filter_op() :: :can_filter_replace | :can_filter_add | :can_filter_remove
Link to this type

cellular_config_response()

View Source
@type cellular_config_response() ::
  :cellular_config_response_accepted
  | :cellular_config_response_apn_error
  | :cellular_config_response_pin_error
  | :cellular_config_response_rejected
  | :cellular_config_blocked_puk_required

Possible responses from a CELLULAR_CONFIG message.

Link to this type

cellular_network_failed_reason()

View Source
@type cellular_network_failed_reason() ::
  :cellular_network_failed_reason_none
  | :cellular_network_failed_reason_unknown
  | :cellular_network_failed_reason_sim_missing
  | :cellular_network_failed_reason_sim_error

These flags are used to diagnose the failure state of CELLULAR_STATUS

Link to this type

cellular_network_radio_type()

View Source
@type cellular_network_radio_type() ::
  :cellular_network_radio_type_none
  | :cellular_network_radio_type_gsm
  | :cellular_network_radio_type_cdma
  | :cellular_network_radio_type_wcdma
  | :cellular_network_radio_type_lte

Cellular network radio type

Link to this type

cellular_status_flag()

View Source
@type cellular_status_flag() ::
  :cellular_status_flag_unknown
  | :cellular_status_flag_failed
  | :cellular_status_flag_initializing
  | :cellular_status_flag_locked
  | :cellular_status_flag_disabled
  | :cellular_status_flag_disabling
  | :cellular_status_flag_enabling
  | :cellular_status_flag_enabled
  | :cellular_status_flag_searching
  | :cellular_status_flag_registered
  | :cellular_status_flag_disconnecting
  | :cellular_status_flag_connecting
  | :cellular_status_flag_connected

These flags encode the cellular network status

@type comp_metadata_type() ::
  :comp_metadata_type_general
  | :comp_metadata_type_parameter
  | :comp_metadata_type_commands
  | :comp_metadata_type_peripherals
  | :comp_metadata_type_events
  | :comp_metadata_type_actuators

Supported component metadata types. These are used in the general metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages.

@type enum_type() ::
  :actuator_configuration
  | :actuator_output_function
  | :adsb_altitude_type
  | :adsb_emitter_type
  | :adsb_flags
  | :ais_flags
  | :ais_nav_status
  | :ais_type
  | :attitude_target_typemask
  | :autotune_axis
  | :camera_cap_flags
  | :camera_mode
  | :camera_tracking_mode
  | :camera_tracking_status_flags
  | :camera_tracking_target_data
  | :camera_zoom_type
  | :can_filter_op
  | :cellular_config_response
  | :cellular_network_failed_reason
  | :cellular_network_radio_type
  | :cellular_status_flag
  | :comp_metadata_type
  | :esc_connection_type
  | :esc_failure_flags
  | :estimator_status_flags
  | :failure_type
  | :failure_unit
  | :fence_action
  | :fence_breach
  | :fence_mitigate
  | :firmware_version_type
  | :gimbal_device_cap_flags
  | :gimbal_device_error_flags
  | :gimbal_device_flags
  | :gimbal_manager_cap_flags
  | :gimbal_manager_flags
  | :gps_fix_type
  | :gps_input_ignore_flags
  | :gripper_actions
  | :highres_imu_updated_flags
  | :hil_sensor_updated_flags
  | :hl_failure_flag
  | :landing_target_type
  | :mag_cal_status
  | :mav_arm_auth_denied_reason
  | :mav_autopilot
  | :mav_battery_charge_state
  | :mav_battery_fault
  | :mav_battery_function
  | :mav_battery_mode
  | :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_event_current_sequence_flags
  | :mav_event_error_reason
  | :mav_frame
  | :mav_ftp_err
  | :mav_ftp_opcode
  | :mav_generator_status_flag
  | :mav_goto
  | :mav_landed_state
  | :mav_mission_result
  | :mav_mission_type
  | :mav_mode
  | :mav_mode_flag
  | :mav_mode_flag_decode_position
  | :mav_mount_mode
  | :mav_odid_arm_status
  | :mav_odid_auth_type
  | :mav_odid_category_eu
  | :mav_odid_class_eu
  | :mav_odid_classification_type
  | :mav_odid_desc_type
  | :mav_odid_height_ref
  | :mav_odid_hor_acc
  | :mav_odid_id_type
  | :mav_odid_operator_id_type
  | :mav_odid_operator_location_type
  | :mav_odid_speed_acc
  | :mav_odid_status
  | :mav_odid_time_acc
  | :mav_odid_ua_type
  | :mav_odid_ver_acc
  | :mav_param_ext_type
  | :mav_param_type
  | :mav_power_status
  | :mav_protocol_capability
  | :mav_result
  | :mav_roi
  | :mav_sensor_orientation
  | :mav_severity
  | :mav_state
  | :mav_sys_status_sensor
  | :mav_sys_status_sensor_extended
  | :mav_tunnel_payload_type
  | :mav_type
  | :mav_vtol_state
  | :mav_winch_status_flag
  | :mavlink_data_stream_type
  | :mission_state
  | :motor_test_order
  | :motor_test_throttle_type
  | :nav_vtol_land_options
  | :orbit_yaw_behaviour
  | :parachute_action
  | :param_ack
  | :position_target_typemask
  | :precision_land_mode
  | :preflight_storage_mission_action
  | :preflight_storage_parameter_action
  | :rc_type
  | :rtk_baseline_coordinate_system
  | :serial_control_dev
  | :serial_control_flag
  | :set_focus_type
  | :storage_status
  | :storage_type
  | :storage_usage_flag
  | :tune_format
  | :uavcan_node_health
  | :uavcan_node_mode
  | :utm_data_avail_flags
  | :utm_flight_state
  | :video_stream_status_flags
  | :video_stream_type
  | :vtol_transition_heading
  | :wifi_config_ap_mode
  | :wifi_config_ap_response
  | :winch_actions

An atom representing a MAVLink enumeration type

@type enum_value() ::
  actuator_configuration()
  | actuator_output_function()
  | adsb_altitude_type()
  | adsb_emitter_type()
  | adsb_flags()
  | ais_flags()
  | ais_nav_status()
  | ais_type()
  | attitude_target_typemask()
  | autotune_axis()
  | camera_cap_flags()
  | camera_mode()
  | camera_tracking_mode()
  | camera_tracking_status_flags()
  | camera_tracking_target_data()
  | camera_zoom_type()
  | can_filter_op()
  | cellular_config_response()
  | cellular_network_failed_reason()
  | cellular_network_radio_type()
  | cellular_status_flag()
  | comp_metadata_type()
  | esc_connection_type()
  | esc_failure_flags()
  | estimator_status_flags()
  | failure_type()
  | failure_unit()
  | fence_action()
  | fence_breach()
  | fence_mitigate()
  | firmware_version_type()
  | gimbal_device_cap_flags()
  | gimbal_device_error_flags()
  | gimbal_device_flags()
  | gimbal_manager_cap_flags()
  | gimbal_manager_flags()
  | gps_fix_type()
  | gps_input_ignore_flags()
  | gripper_actions()
  | highres_imu_updated_flags()
  | hil_sensor_updated_flags()
  | hl_failure_flag()
  | landing_target_type()
  | mag_cal_status()
  | mav_arm_auth_denied_reason()
  | mav_autopilot()
  | mav_battery_charge_state()
  | mav_battery_fault()
  | mav_battery_function()
  | mav_battery_mode()
  | 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_event_current_sequence_flags()
  | mav_event_error_reason()
  | mav_frame()
  | mav_ftp_err()
  | mav_ftp_opcode()
  | mav_generator_status_flag()
  | mav_goto()
  | mav_landed_state()
  | mav_mission_result()
  | mav_mission_type()
  | mav_mode()
  | mav_mode_flag()
  | mav_mode_flag_decode_position()
  | mav_mount_mode()
  | mav_odid_arm_status()
  | mav_odid_auth_type()
  | mav_odid_category_eu()
  | mav_odid_class_eu()
  | mav_odid_classification_type()
  | mav_odid_desc_type()
  | mav_odid_height_ref()
  | mav_odid_hor_acc()
  | mav_odid_id_type()
  | mav_odid_operator_id_type()
  | mav_odid_operator_location_type()
  | mav_odid_speed_acc()
  | mav_odid_status()
  | mav_odid_time_acc()
  | mav_odid_ua_type()
  | mav_odid_ver_acc()
  | mav_param_ext_type()
  | mav_param_type()
  | mav_power_status()
  | mav_protocol_capability()
  | mav_result()
  | mav_roi()
  | mav_sensor_orientation()
  | mav_severity()
  | mav_state()
  | mav_sys_status_sensor()
  | mav_sys_status_sensor_extended()
  | mav_tunnel_payload_type()
  | mav_type()
  | mav_vtol_state()
  | mav_winch_status_flag()
  | mavlink_data_stream_type()
  | mission_state()
  | motor_test_order()
  | motor_test_throttle_type()
  | nav_vtol_land_options()
  | orbit_yaw_behaviour()
  | parachute_action()
  | param_ack()
  | position_target_typemask()
  | precision_land_mode()
  | preflight_storage_mission_action()
  | preflight_storage_parameter_action()
  | rc_type()
  | rtk_baseline_coordinate_system()
  | serial_control_dev()
  | serial_control_flag()
  | set_focus_type()
  | storage_status()
  | storage_type()
  | storage_usage_flag()
  | tune_format()
  | uavcan_node_health()
  | uavcan_node_mode()
  | utm_data_avail_flags()
  | utm_flight_state()
  | video_stream_status_flags()
  | video_stream_type()
  | vtol_transition_heading()
  | wifi_config_ap_mode()
  | wifi_config_ap_response()
  | winch_actions()

An atom representing a MAVLink enumeration type value

@type esc_connection_type() ::
  :esc_connection_type_ppm
  | :esc_connection_type_serial
  | :esc_connection_type_oneshot
  | :esc_connection_type_i2c
  | :esc_connection_type_can
  | :esc_connection_type_dshot

Indicates the ESC connection type.

@type esc_failure_flags() ::
  :esc_failure_none
  | :esc_failure_over_current
  | :esc_failure_over_voltage
  | :esc_failure_over_temperature
  | :esc_failure_over_rpm
  | :esc_failure_inconsistent_cmd
  | :esc_failure_motor_stuck
  | :esc_failure_generic

Flags to report ESC failures.

Link to this type

estimator_status_flags()

View Source
@type 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 ESTIMATOR_STATUS message

@type failure_type() ::
  :failure_type_ok
  | :failure_type_off
  | :failure_type_stuck
  | :failure_type_garbage
  | :failure_type_wrong
  | :failure_type_slow
  | :failure_type_delayed
  | :failure_type_intermittent

List of possible failure type to inject.

@type failure_unit() ::
  :failure_unit_sensor_gyro
  | :failure_unit_sensor_accel
  | :failure_unit_sensor_mag
  | :failure_unit_sensor_baro
  | :failure_unit_sensor_gps
  | :failure_unit_sensor_optical_flow
  | :failure_unit_sensor_vio
  | :failure_unit_sensor_distance_sensor
  | :failure_unit_sensor_airspeed
  | :failure_unit_system_battery
  | :failure_unit_system_motor
  | :failure_unit_system_servo
  | :failure_unit_system_avoidance
  | :failure_unit_system_rc_signal
  | :failure_unit_system_mavlink_signal

List of possible units where failures can be injected.

@type fence_action() ::
  :fence_action_none
  | :fence_action_guided
  | :fence_action_report
  | :fence_action_guided_thr_pass
  | :fence_action_rtl
  | :fence_action_hold
  | :fence_action_terminate
  | :fence_action_land

Actions following geofence breach.

@type fence_breach() ::
  :fence_breach_none
  | :fence_breach_minalt
  | :fence_breach_maxalt
  | :fence_breach_boundary
@type fence_mitigate() ::
  :fence_mitigate_unknown | :fence_mitigate_none | :fence_mitigate_vel_limit

Actions being taken to mitigate/prevent fence breach

@type field_unit() ::
  :%
  | :"KiB/s"
  | :"MiB/s"
  | :"bits/s"
  | :"bytes/s"
  | :"c%"
  | :"cdeg/s"
  | :"cm/s"
  | :"cm^2"
  | :"cm^3"
  | :"cm^3/min"
  | :"d%"
  | :"deg/2"
  | :"dm/s"
  | :"m/s"
  | :"m/s*5"
  | :"m/s/s"
  | :"mrad/s"
  | :"rad/s"
  | :A
  | :Hz
  | :MiB
  | :V
  | :W
  | :bytes
  | :cA
  | :cdeg
  | :cdegC
  | :cm
  | :cs
  | :dB
  | :dam
  | :deg
  | :degC
  | :degE5
  | :degE7
  | :dm
  | :dpix
  | :g
  | :gauss
  | :hJ
  | :hPa
  | :kPa
  | :kg
  | :m
  | :mA
  | :mAh
  | :mG
  | :mV
  | :mgauss
  | :mm
  | :ms
  | :ns
  | :pix
  | :rad
  | :rpm
  | :s
  | :us

Measurement unit of field value

Link to this type

firmware_version_type()

View Source
@type 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_device_cap_flags()

View Source
@type gimbal_device_cap_flags() ::
  :gimbal_device_cap_flags_has_retract
  | :gimbal_device_cap_flags_has_neutral
  | :gimbal_device_cap_flags_has_roll_axis
  | :gimbal_device_cap_flags_has_roll_follow
  | :gimbal_device_cap_flags_has_roll_lock
  | :gimbal_device_cap_flags_has_pitch_axis
  | :gimbal_device_cap_flags_has_pitch_follow
  | :gimbal_device_cap_flags_has_pitch_lock
  | :gimbal_device_cap_flags_has_yaw_axis
  | :gimbal_device_cap_flags_has_yaw_follow
  | :gimbal_device_cap_flags_has_yaw_lock
  | :gimbal_device_cap_flags_supports_infinite_yaw
  | :gimbal_device_cap_flags_supports_yaw_in_earth_frame
  | :gimbal_device_cap_flags_has_rc_inputs

Gimbal device (low level) capability flags (bitmap).

Link to this type

gimbal_device_error_flags()

View Source
@type gimbal_device_error_flags() ::
  :gimbal_device_error_flags_at_roll_limit
  | :gimbal_device_error_flags_at_pitch_limit
  | :gimbal_device_error_flags_at_yaw_limit
  | :gimbal_device_error_flags_encoder_error
  | :gimbal_device_error_flags_power_error
  | :gimbal_device_error_flags_motor_error
  | :gimbal_device_error_flags_software_error
  | :gimbal_device_error_flags_comms_error
  | :gimbal_device_error_flags_calibration_running
  | :gimbal_device_error_flags_no_manager

Gimbal device (low level) error flags (bitmap, 0 means no error)

@type gimbal_device_flags() ::
  :gimbal_device_flags_retract
  | :gimbal_device_flags_neutral
  | :gimbal_device_flags_roll_lock
  | :gimbal_device_flags_pitch_lock
  | :gimbal_device_flags_yaw_lock
  | :gimbal_device_flags_yaw_in_vehicle_frame
  | :gimbal_device_flags_yaw_in_earth_frame
  | :gimbal_device_flags_accepts_yaw_in_earth_frame
  | :gimbal_device_flags_rc_exclusive
  | :gimbal_device_flags_rc_mixed

Flags for gimbal device (lower level) operation.

Link to this type

gimbal_manager_cap_flags()

View Source
@type gimbal_manager_cap_flags() ::
  :gimbal_manager_cap_flags_has_retract
  | :gimbal_manager_cap_flags_has_neutral
  | :gimbal_manager_cap_flags_has_roll_axis
  | :gimbal_manager_cap_flags_has_roll_follow
  | :gimbal_manager_cap_flags_has_roll_lock
  | :gimbal_manager_cap_flags_has_pitch_axis
  | :gimbal_manager_cap_flags_has_pitch_follow
  | :gimbal_manager_cap_flags_has_pitch_lock
  | :gimbal_manager_cap_flags_has_yaw_axis
  | :gimbal_manager_cap_flags_has_yaw_follow
  | :gimbal_manager_cap_flags_has_yaw_lock
  | :gimbal_manager_cap_flags_supports_infinite_yaw
  | :gimbal_manager_cap_flags_supports_yaw_in_earth_frame
  | :gimbal_manager_cap_flags_has_rc_inputs
  | :gimbal_manager_cap_flags_can_point_location_local
  | :gimbal_manager_cap_flags_can_point_location_global

Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags.

Link to this type

gimbal_manager_flags()

View Source
@type gimbal_manager_flags() ::
  :gimbal_manager_flags_retract
  | :gimbal_manager_flags_neutral
  | :gimbal_manager_flags_roll_lock
  | :gimbal_manager_flags_pitch_lock
  | :gimbal_manager_flags_yaw_lock
  | :gimbal_manager_flags_yaw_in_vehicle_frame
  | :gimbal_manager_flags_yaw_in_earth_frame
  | :gimbal_manager_flags_accepts_yaw_in_earth_frame
  | :gimbal_manager_flags_rc_exclusive
  | :gimbal_manager_flags_rc_mixed

Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.

@type 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
@type 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
@type gripper_actions() :: :gripper_action_release | :gripper_action_grab

Gripper actions.

Link to this type

highres_imu_updated_flags()

View Source
@type highres_imu_updated_flags() ::
  :highres_imu_updated_none
  | :highres_imu_updated_xacc
  | :highres_imu_updated_yacc
  | :highres_imu_updated_zacc
  | :highres_imu_updated_xgyro
  | :highres_imu_updated_ygyro
  | :highres_imu_updated_zgyro
  | :highres_imu_updated_xmag
  | :highres_imu_updated_ymag
  | :highres_imu_updated_zmag
  | :highres_imu_updated_abs_pressure
  | :highres_imu_updated_diff_pressure
  | :highres_imu_updated_pressure_alt
  | :highres_imu_updated_temperature
  | :highres_imu_updated_all

Flags in the HIGHRES_IMU message indicate which fields have updated since the last message

Link to this type

hil_sensor_updated_flags()

View Source
@type hil_sensor_updated_flags() ::
  :hil_sensor_updated_none
  | :hil_sensor_updated_xacc
  | :hil_sensor_updated_yacc
  | :hil_sensor_updated_zacc
  | :hil_sensor_updated_xgyro
  | :hil_sensor_updated_ygyro
  | :hil_sensor_updated_zgyro
  | :hil_sensor_updated_xmag
  | :hil_sensor_updated_ymag
  | :hil_sensor_updated_zmag
  | :hil_sensor_updated_abs_pressure
  | :hil_sensor_updated_diff_pressure
  | :hil_sensor_updated_pressure_alt
  | :hil_sensor_updated_temperature
  | :hil_sensor_updated_reset

Flags in the HIL_SENSOR message indicate which fields have updated since the last message

@type hl_failure_flag() ::
  :hl_failure_flag_gps
  | :hl_failure_flag_differential_pressure
  | :hl_failure_flag_absolute_pressure
  | :hl_failure_flag_3d_accel
  | :hl_failure_flag_3d_gyro
  | :hl_failure_flag_3d_mag
  | :hl_failure_flag_terrain
  | :hl_failure_flag_battery
  | :hl_failure_flag_rc_receiver
  | :hl_failure_flag_offboard_link
  | :hl_failure_flag_engine
  | :hl_failure_flag_geofence
  | :hl_failure_flag_estimator
  | :hl_failure_flag_mission

Flags to report failure cases over the high latency telemtry.

@type 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

@type 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
  | :mag_cal_bad_radius
Link to this type

mav_arm_auth_denied_reason()

View Source
@type 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
@type 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
  | :mav_autopilot_reflex

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

Link to this type

mav_battery_charge_state()

View Source
@type 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.

@type mav_battery_fault() ::
  :mav_battery_fault_deep_discharge
  | :mav_battery_fault_spikes
  | :mav_battery_fault_cell_fail
  | :mav_battery_fault_over_current
  | :mav_battery_fault_over_temperature
  | :mav_battery_fault_under_temperature
  | :mav_battery_fault_incompatible_voltage
  | :mav_battery_fault_incompatible_firmware
  | :battery_fault_incompatible_cells_configuration

Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set.

Link to this type

mav_battery_function()

View Source
@type 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

@type mav_battery_mode() ::
  :mav_battery_mode_unknown
  | :mav_battery_mode_auto_discharging
  | :mav_battery_mode_hot_swap

Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight.

@type 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

@type 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_do_orbit
  | :mav_cmd_nav_roi
  | :mav_cmd_nav_pathplanning
  | :mav_cmd_nav_spline_waypoint
  | :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_set_actuator
  | :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_set_roi_sysid
  | :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_oblique_survey
  | :mav_cmd_mission_start
  | :mav_cmd_actuator_test
  | :mav_cmd_configure_actuator
  | :mav_cmd_component_arm_disarm
  | :mav_cmd_run_prearm_checks
  | :mav_cmd_illuminator_on_off
  | :mav_cmd_get_home_position
  | :mav_cmd_inject_failure
  | :mav_cmd_start_rx_pair
  | :mav_cmd_get_message_interval
  | :mav_cmd_set_message_interval
  | :mav_cmd_request_message
  | :mav_cmd_request_protocol_version
  | :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_set_camera_zoom
  | :mav_cmd_set_camera_focus
  | :mav_cmd_set_storage_usage
  | :mav_cmd_jump_tag
  | :mav_cmd_do_jump_tag
  | :mav_cmd_do_gimbal_manager_pitchyaw
  | :mav_cmd_do_gimbal_manager_configure
  | :mav_cmd_image_start_capture
  | :mav_cmd_image_stop_capture
  | :mav_cmd_request_camera_image_capture
  | :mav_cmd_do_trigger_control
  | :mav_cmd_camera_track_point
  | :mav_cmd_camera_track_rectangle
  | :mav_cmd_camera_stop_tracking
  | :mav_cmd_video_start_capture
  | :mav_cmd_video_stop_capture
  | :mav_cmd_video_start_streaming
  | :mav_cmd_video_stop_streaming
  | :mav_cmd_request_video_stream_information
  | :mav_cmd_request_video_stream_status
  | :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_condition_gate
  | :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_do_adsb_out_ident
  | :mav_cmd_payload_prepare_deploy
  | :mav_cmd_payload_control_deploy
  | :mav_cmd_fixed_mag_cal_yaw
  | :mav_cmd_do_winch
  | :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_can_forward

Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries

@type 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
@type 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.

@type 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
@type 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.

@type mav_component() ::
  :mav_comp_id_all
  | :mav_comp_id_autopilot1
  | :mav_comp_id_user1
  | :mav_comp_id_user2
  | :mav_comp_id_user3
  | :mav_comp_id_user4
  | :mav_comp_id_user5
  | :mav_comp_id_user6
  | :mav_comp_id_user7
  | :mav_comp_id_user8
  | :mav_comp_id_user9
  | :mav_comp_id_user10
  | :mav_comp_id_user11
  | :mav_comp_id_user12
  | :mav_comp_id_user13
  | :mav_comp_id_user14
  | :mav_comp_id_user15
  | :mav_comp_id_user16
  | :mav_comp_id_user17
  | :mav_comp_id_user18
  | :mav_comp_id_user19
  | :mav_comp_id_user20
  | :mav_comp_id_user21
  | :mav_comp_id_user22
  | :mav_comp_id_user23
  | :mav_comp_id_user24
  | :mav_comp_id_user25
  | :mav_comp_id_user26
  | :mav_comp_id_user27
  | :mav_comp_id_user28
  | :mav_comp_id_user29
  | :mav_comp_id_user30
  | :mav_comp_id_user31
  | :mav_comp_id_user32
  | :mav_comp_id_user33
  | :mav_comp_id_user34
  | :mav_comp_id_user35
  | :mav_comp_id_user36
  | :mav_comp_id_user37
  | :mav_comp_id_user38
  | :mav_comp_id_user39
  | :mav_comp_id_user40
  | :mav_comp_id_user41
  | :mav_comp_id_user42
  | :mav_comp_id_user43
  | :mav_comp_id_telemetry_radio
  | :mav_comp_id_user45
  | :mav_comp_id_user46
  | :mav_comp_id_user47
  | :mav_comp_id_user48
  | :mav_comp_id_user49
  | :mav_comp_id_user50
  | :mav_comp_id_user51
  | :mav_comp_id_user52
  | :mav_comp_id_user53
  | :mav_comp_id_user54
  | :mav_comp_id_user55
  | :mav_comp_id_user56
  | :mav_comp_id_user57
  | :mav_comp_id_user58
  | :mav_comp_id_user59
  | :mav_comp_id_user60
  | :mav_comp_id_user61
  | :mav_comp_id_user62
  | :mav_comp_id_user63
  | :mav_comp_id_user64
  | :mav_comp_id_user65
  | :mav_comp_id_user66
  | :mav_comp_id_user67
  | :mav_comp_id_user68
  | :mav_comp_id_user69
  | :mav_comp_id_user70
  | :mav_comp_id_user71
  | :mav_comp_id_user72
  | :mav_comp_id_user73
  | :mav_comp_id_user74
  | :mav_comp_id_user75
  | :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_parachute
  | :mav_comp_id_winch
  | :mav_comp_id_gimbal2
  | :mav_comp_id_gimbal3
  | :mav_comp_id_gimbal4
  | :mav_comp_id_gimbal5
  | :mav_comp_id_gimbal6
  | :mav_comp_id_battery
  | :mav_comp_id_battery2
  | :mav_comp_id_mavcan
  | :mav_comp_id_missionplanner
  | :mav_comp_id_onboard_computer
  | :mav_comp_id_onboard_computer2
  | :mav_comp_id_onboard_computer3
  | :mav_comp_id_onboard_computer4
  | :mav_comp_id_pathplanner
  | :mav_comp_id_obstacle_avoidance
  | :mav_comp_id_visual_inertial_odometry
  | :mav_comp_id_pairing_manager
  | :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_odid_txrx_1
  | :mav_comp_id_odid_txrx_2
  | :mav_comp_id_odid_txrx_3
  | :mav_comp_id_udp_bridge
  | :mav_comp_id_uart_bridge
  | :mav_comp_id_tunnel_node
  | :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.

@type 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.

@type 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
@type mav_do_reposition_flags() :: :mav_do_reposition_flags_change_mode

Bitmap of options for the MAV_CMD_DO_REPOSITION

@type mav_estimator_type() ::
  :mav_estimator_type_unknown
  | :mav_estimator_type_naive
  | :mav_estimator_type_vision
  | :mav_estimator_type_vio
  | :mav_estimator_type_gps
  | :mav_estimator_type_gps_ins
  | :mav_estimator_type_mocap
  | :mav_estimator_type_lidar
  | :mav_estimator_type_autopilot

Enumeration of estimator types

Link to this type

mav_event_current_sequence_flags()

View Source
@type mav_event_current_sequence_flags() :: :mav_event_current_sequence_flags_reset

Flags for CURRENT_EVENT_SEQUENCE.

Link to this type

mav_event_error_reason()

View Source
@type mav_event_error_reason() :: :mav_event_error_reason_unavailable

Reason for an event error response.

@type 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_reserved_13
  | :mav_frame_reserved_14
  | :mav_frame_reserved_15
  | :mav_frame_reserved_16
  | :mav_frame_reserved_17
  | :mav_frame_reserved_18
  | :mav_frame_reserved_19
  | :mav_frame_local_frd
  | :mav_frame_local_flu

Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - 'GLOBAL': Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with 'GLOBAL': - 'RELATIVE_ALT': Altitude is relative to the vehicle home position rather than MSL. - 'TERRAIN_ALT': Altitude is relative to ground level rather than MSL. - 'INT': Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - 'LOCAL': Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator ('EKF'). - 'BODY': Origin of local frame travels with the vehicle. NOTE, 'BODY' does NOT indicate alignment of frame axis with vehicle attitude. - 'OFFSET': Deprecated synonym for 'BODY' (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).

@type mav_ftp_err() ::
  :mav_ftp_err_none
  | :mav_ftp_err_fail
  | :mav_ftp_err_failerrno
  | :mav_ftp_err_invaliddatasize
  | :mav_ftp_err_invalidsession
  | :mav_ftp_err_nosessionsavailable
  | :mav_ftp_err_eof
  | :mav_ftp_err_unknowncommand
  | :mav_ftp_err_fileexists
  | :mav_ftp_err_fileprotected
  | :mav_ftp_err_filenotfound

MAV FTP error codes (https://mavlink.io/en/services/ftp.html)

@type mav_ftp_opcode() ::
  :mav_ftp_opcode_none
  | :mav_ftp_opcode_terminatesession
  | :mav_ftp_opcode_resetsession
  | :mav_ftp_opcode_listdirectory
  | :mav_ftp_opcode_openfilero
  | :mav_ftp_opcode_readfile
  | :mav_ftp_opcode_createfile
  | :mav_ftp_opcode_writefile
  | :mav_ftp_opcode_removefile
  | :mav_ftp_opcode_createdirectory
  | :mav_ftp_opcode_removedirectory
  | :mav_ftp_opcode_openfilewo
  | :mav_ftp_opcode_truncatefile
  | :mav_ftp_opcode_rename
  | :mav_ftp_opcode_calcfilecrc
  | :mav_ftp_opcode_burstreadfile
  | :mav_ftp_opcode_ack
  | :mav_ftp_opcode_nak

MAV FTP opcodes: https://mavlink.io/en/services/ftp.html

Link to this type

mav_generator_status_flag()

View Source
@type mav_generator_status_flag() ::
  :mav_generator_status_flag_off
  | :mav_generator_status_flag_ready
  | :mav_generator_status_flag_generating
  | :mav_generator_status_flag_charging
  | :mav_generator_status_flag_reduced_power
  | :mav_generator_status_flag_maxpower
  | :mav_generator_status_flag_overtemp_warning
  | :mav_generator_status_flag_overtemp_fault
  | :mav_generator_status_flag_electronics_overtemp_warning
  | :mav_generator_status_flag_electronics_overtemp_fault
  | :mav_generator_status_flag_electronics_fault
  | :mav_generator_status_flag_powersource_fault
  | :mav_generator_status_flag_communication_warning
  | :mav_generator_status_flag_cooling_warning
  | :mav_generator_status_flag_power_rail_fault
  | :mav_generator_status_flag_overcurrent_fault
  | :mav_generator_status_flag_battery_overcharge_current_fault
  | :mav_generator_status_flag_overvoltage_fault
  | :mav_generator_status_flag_battery_undervolt_fault
  | :mav_generator_status_flag_start_inhibited
  | :mav_generator_status_flag_maintenance_required
  | :mav_generator_status_flag_warming_up
  | :mav_generator_status_flag_idle

Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).

@type 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.

@type 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

@type 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).

@type 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.

@type 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.

@type 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
@type 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.

@type 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
  | :mav_mount_mode_sysid_target
  | :mav_mount_mode_home_location

Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.

@type mav_odid_arm_status() ::
  :mav_odid_arm_status_good_to_arm | :mav_odid_arm_status_pre_arm_fail_generic
@type mav_odid_auth_type() ::
  :mav_odid_auth_type_none
  | :mav_odid_auth_type_uas_id_signature
  | :mav_odid_auth_type_operator_id_signature
  | :mav_odid_auth_type_message_set_signature
  | :mav_odid_auth_type_network_remote_id
  | :mav_odid_auth_type_specific_authentication
Link to this type

mav_odid_category_eu()

View Source
@type mav_odid_category_eu() ::
  :mav_odid_category_eu_undeclared
  | :mav_odid_category_eu_open
  | :mav_odid_category_eu_specific
  | :mav_odid_category_eu_certified
@type mav_odid_class_eu() ::
  :mav_odid_class_eu_undeclared
  | :mav_odid_class_eu_class_0
  | :mav_odid_class_eu_class_1
  | :mav_odid_class_eu_class_2
  | :mav_odid_class_eu_class_3
  | :mav_odid_class_eu_class_4
  | :mav_odid_class_eu_class_5
  | :mav_odid_class_eu_class_6
Link to this type

mav_odid_classification_type()

View Source
@type mav_odid_classification_type() ::
  :mav_odid_classification_type_undeclared | :mav_odid_classification_type_eu
@type mav_odid_desc_type() ::
  :mav_odid_desc_type_text
  | :mav_odid_desc_type_emergency
  | :mav_odid_desc_type_extended_status
@type mav_odid_height_ref() ::
  :mav_odid_height_ref_over_takeoff | :mav_odid_height_ref_over_ground
@type mav_odid_hor_acc() ::
  :mav_odid_hor_acc_unknown
  | :mav_odid_hor_acc_10nm
  | :mav_odid_hor_acc_4nm
  | :mav_odid_hor_acc_2nm
  | :mav_odid_hor_acc_1nm
  | :mav_odid_hor_acc_0_5nm
  | :mav_odid_hor_acc_0_3nm
  | :mav_odid_hor_acc_0_1nm
  | :mav_odid_hor_acc_0_05nm
  | :mav_odid_hor_acc_30_meter
  | :mav_odid_hor_acc_10_meter
  | :mav_odid_hor_acc_3_meter
  | :mav_odid_hor_acc_1_meter
@type mav_odid_id_type() ::
  :mav_odid_id_type_none
  | :mav_odid_id_type_serial_number
  | :mav_odid_id_type_caa_registration_id
  | :mav_odid_id_type_utm_assigned_uuid
  | :mav_odid_id_type_specific_session_id
Link to this type

mav_odid_operator_id_type()

View Source
@type mav_odid_operator_id_type() :: :mav_odid_operator_id_type_caa
Link to this type

mav_odid_operator_location_type()

View Source
@type mav_odid_operator_location_type() ::
  :mav_odid_operator_location_type_takeoff
  | :mav_odid_operator_location_type_live_gnss
  | :mav_odid_operator_location_type_fixed
@type mav_odid_speed_acc() ::
  :mav_odid_speed_acc_unknown
  | :mav_odid_speed_acc_10_meters_per_second
  | :mav_odid_speed_acc_3_meters_per_second
  | :mav_odid_speed_acc_1_meters_per_second
  | :mav_odid_speed_acc_0_3_meters_per_second
@type mav_odid_status() ::
  :mav_odid_status_undeclared
  | :mav_odid_status_ground
  | :mav_odid_status_airborne
  | :mav_odid_status_emergency
  | :mav_odid_status_remote_id_system_failure
@type mav_odid_time_acc() ::
  :mav_odid_time_acc_unknown
  | :mav_odid_time_acc_0_1_second
  | :mav_odid_time_acc_0_2_second
  | :mav_odid_time_acc_0_3_second
  | :mav_odid_time_acc_0_4_second
  | :mav_odid_time_acc_0_5_second
  | :mav_odid_time_acc_0_6_second
  | :mav_odid_time_acc_0_7_second
  | :mav_odid_time_acc_0_8_second
  | :mav_odid_time_acc_0_9_second
  | :mav_odid_time_acc_1_0_second
  | :mav_odid_time_acc_1_1_second
  | :mav_odid_time_acc_1_2_second
  | :mav_odid_time_acc_1_3_second
  | :mav_odid_time_acc_1_4_second
  | :mav_odid_time_acc_1_5_second
@type mav_odid_ua_type() ::
  :mav_odid_ua_type_none
  | :mav_odid_ua_type_aeroplane
  | :mav_odid_ua_type_helicopter_or_multirotor
  | :mav_odid_ua_type_gyroplane
  | :mav_odid_ua_type_hybrid_lift
  | :mav_odid_ua_type_ornithopter
  | :mav_odid_ua_type_glider
  | :mav_odid_ua_type_kite
  | :mav_odid_ua_type_free_balloon
  | :mav_odid_ua_type_captive_balloon
  | :mav_odid_ua_type_airship
  | :mav_odid_ua_type_free_fall_parachute
  | :mav_odid_ua_type_rocket
  | :mav_odid_ua_type_tethered_powered_aircraft
  | :mav_odid_ua_type_ground_obstacle
  | :mav_odid_ua_type_other
@type mav_odid_ver_acc() ::
  :mav_odid_ver_acc_unknown
  | :mav_odid_ver_acc_150_meter
  | :mav_odid_ver_acc_45_meter
  | :mav_odid_ver_acc_25_meter
  | :mav_odid_ver_acc_10_meter
  | :mav_odid_ver_acc_3_meter
  | :mav_odid_ver_acc_1_meter
@type mav_param_ext_type() ::
  :mav_param_ext_type_uint8
  | :mav_param_ext_type_int8
  | :mav_param_ext_type_uint16
  | :mav_param_ext_type_int16
  | :mav_param_ext_type_uint32
  | :mav_param_ext_type_int32
  | :mav_param_ext_type_uint64
  | :mav_param_ext_type_int64
  | :mav_param_ext_type_real32
  | :mav_param_ext_type_real64
  | :mav_param_ext_type_custom

Specifies the datatype of a MAVLink extended parameter.

@type 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.

@type 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
@type 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_encode_bytewise
  | :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_reserved2
  | :mav_protocol_capability_param_encode_c_cast

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

@type mav_result() ::
  :mav_result_accepted
  | :mav_result_temporarily_rejected
  | :mav_result_denied
  | :mav_result_unsupported
  | :mav_result_failed
  | :mav_result_in_progress
  | :mav_result_cancelled

Result from a MAVLink command (MAV_CMD)

@type mav_roi() ::
  :mav_roi_none
  | :mav_roi_wpnext
  | :mav_roi_wpindex
  | :mav_roi_location
  | :mav_roi_target

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
@type 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

@type 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/.

@type 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
@type 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
  | :mav_sys_status_prearm_check
  | :mav_sys_status_obstacle_avoidance
  | :mav_sys_status_sensor_propulsion
  | :mav_sys_status_extension_used

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

Link to this type

mav_sys_status_sensor_extended()

View Source
@type mav_sys_status_sensor_extended() :: :mav_sys_status_recovery_system

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

Link to this type

mav_tunnel_payload_type()

View Source
@type mav_tunnel_payload_type() ::
  :mav_tunnel_payload_type_unknown
  | :mav_tunnel_payload_type_storm32_reserved0
  | :mav_tunnel_payload_type_storm32_reserved1
  | :mav_tunnel_payload_type_storm32_reserved2
  | :mav_tunnel_payload_type_storm32_reserved3
  | :mav_tunnel_payload_type_storm32_reserved4
  | :mav_tunnel_payload_type_storm32_reserved5
  | :mav_tunnel_payload_type_storm32_reserved6
  | :mav_tunnel_payload_type_storm32_reserved7
  | :mav_tunnel_payload_type_storm32_reserved8
  | :mav_tunnel_payload_type_storm32_reserved9
@type 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_tailsitter_duorotor
  | :mav_type_vtol_tailsitter_quadrotor
  | :mav_type_vtol_tiltrotor
  | :mav_type_vtol_fixedrotor
  | :mav_type_vtol_tailsitter
  | :mav_type_vtol_tiltwing
  | :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
  | :mav_type_servo
  | :mav_type_odid
  | :mav_type_decarotor
  | :mav_type_battery
  | :mav_type_parachute
  | :mav_type_log
  | :mav_type_osd
  | :mav_type_imu
  | :mav_type_gps
  | :mav_type_winch

MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).

@type 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

mav_winch_status_flag()

View Source
@type mav_winch_status_flag() ::
  :mav_winch_status_healthy
  | :mav_winch_status_fully_retracted
  | :mav_winch_status_moving
  | :mav_winch_status_clutch_engaged
  | :mav_winch_status_locked
  | :mav_winch_status_dropping
  | :mav_winch_status_arresting
  | :mav_winch_status_ground_sense
  | :mav_winch_status_retracting
  | :mav_winch_status_redeliver
  | :mav_winch_status_abandon_line
  | :mav_winch_status_locking
  | :mav_winch_status_load_line
  | :mav_winch_status_load_payload

Winch status flags used in WINCH_STATUS

@type message() ::
  Common.Message.Heartbeat
  | Common.Message.SysStatus
  | Common.Message.SystemTime
  | Common.Message.Ping
  | Common.Message.ChangeOperatorControl
  | Common.Message.ChangeOperatorControlAck
  | Common.Message.AuthKey
  | Common.Message.LinkNodeStatus
  | Common.Message.SetMode
  | Common.Message.ParamRequestRead
  | Common.Message.ParamRequestList
  | Common.Message.ParamValue
  | Common.Message.ParamSet
  | Common.Message.GpsRawInt
  | Common.Message.GpsStatus
  | Common.Message.ScaledImu
  | Common.Message.RawImu
  | Common.Message.RawPressure
  | Common.Message.ScaledPressure
  | Common.Message.Attitude
  | Common.Message.AttitudeQuaternion
  | Common.Message.LocalPositionNed
  | Common.Message.GlobalPositionInt
  | Common.Message.RcChannelsScaled
  | Common.Message.RcChannelsRaw
  | Common.Message.ServoOutputRaw
  | Common.Message.MissionRequestPartialList
  | Common.Message.MissionWritePartialList
  | Common.Message.MissionItem
  | Common.Message.MissionRequest
  | Common.Message.MissionSetCurrent
  | Common.Message.MissionCurrent
  | Common.Message.MissionRequestList
  | Common.Message.MissionCount
  | Common.Message.MissionClearAll
  | Common.Message.MissionItemReached
  | Common.Message.MissionAck
  | Common.Message.SetGpsGlobalOrigin
  | Common.Message.GpsGlobalOrigin
  | Common.Message.ParamMapRc
  | Common.Message.MissionRequestInt
  | Common.Message.SafetySetAllowedArea
  | Common.Message.SafetyAllowedArea
  | Common.Message.AttitudeQuaternionCov
  | Common.Message.NavControllerOutput
  | Common.Message.GlobalPositionIntCov
  | Common.Message.LocalPositionNedCov
  | Common.Message.RcChannels
  | Common.Message.RequestDataStream
  | Common.Message.DataStream
  | Common.Message.ManualControl
  | Common.Message.RcChannelsOverride
  | Common.Message.MissionItemInt
  | Common.Message.VfrHud
  | Common.Message.CommandInt
  | Common.Message.CommandLong
  | Common.Message.CommandAck
  | Common.Message.CommandCancel
  | Common.Message.ManualSetpoint
  | Common.Message.SetAttitudeTarget
  | Common.Message.AttitudeTarget
  | Common.Message.SetPositionTargetLocalNed
  | Common.Message.PositionTargetLocalNed
  | Common.Message.SetPositionTargetGlobalInt
  | Common.Message.PositionTargetGlobalInt
  | Common.Message.LocalPositionNedSystemGlobalOffset
  | Common.Message.HilState
  | Common.Message.HilControls
  | Common.Message.HilRcInputsRaw
  | Common.Message.HilActuatorControls
  | Common.Message.OpticalFlow
  | Common.Message.GlobalVisionPositionEstimate
  | Common.Message.VisionPositionEstimate
  | Common.Message.VisionSpeedEstimate
  | Common.Message.ViconPositionEstimate
  | Common.Message.HighresImu
  | Common.Message.OpticalFlowRad
  | Common.Message.HilSensor
  | Common.Message.SimState
  | Common.Message.RadioStatus
  | Common.Message.FileTransferProtocol
  | Common.Message.Timesync
  | Common.Message.CameraTrigger
  | Common.Message.HilGps
  | Common.Message.HilOpticalFlow
  | Common.Message.HilStateQuaternion
  | Common.Message.ScaledImu2
  | Common.Message.LogRequestList
  | Common.Message.LogEntry
  | Common.Message.LogRequestData
  | Common.Message.LogData
  | Common.Message.LogErase
  | Common.Message.LogRequestEnd
  | Common.Message.GpsInjectData
  | Common.Message.Gps2Raw
  | Common.Message.PowerStatus
  | Common.Message.SerialControl
  | Common.Message.GpsRtk
  | Common.Message.Gps2Rtk
  | Common.Message.ScaledImu3
  | Common.Message.DataTransmissionHandshake
  | Common.Message.EncapsulatedData
  | Common.Message.DistanceSensor
  | Common.Message.TerrainRequest
  | Common.Message.TerrainData
  | Common.Message.TerrainCheck
  | Common.Message.TerrainReport
  | Common.Message.ScaledPressure2
  | Common.Message.AttPosMocap
  | Common.Message.SetActuatorControlTarget
  | Common.Message.ActuatorControlTarget
  | Common.Message.Altitude
  | Common.Message.ResourceRequest
  | Common.Message.ScaledPressure3
  | Common.Message.FollowTarget
  | Common.Message.ControlSystemState
  | Common.Message.BatteryStatus
  | Common.Message.AutopilotVersion
  | Common.Message.LandingTarget
  | Common.Message.FenceStatus
  | Common.Message.MagCalReport
  | Common.Message.EfiStatus
  | Common.Message.EstimatorStatus
  | Common.Message.WindCov
  | Common.Message.GpsInput
  | Common.Message.GpsRtcmData
  | Common.Message.HighLatency
  | Common.Message.HighLatency2
  | Common.Message.Vibration
  | Common.Message.HomePosition
  | Common.Message.SetHomePosition
  | Common.Message.MessageInterval
  | Common.Message.ExtendedSysState
  | Common.Message.AdsbVehicle
  | Common.Message.Collision
  | Common.Message.V2Extension
  | Common.Message.MemoryVect
  | Common.Message.DebugVect
  | Common.Message.NamedValueFloat
  | Common.Message.NamedValueInt
  | Common.Message.Statustext
  | Common.Message.Debug
  | Common.Message.SetupSigning
  | Common.Message.ButtonChange
  | Common.Message.PlayTune
  | Common.Message.CameraInformation
  | Common.Message.CameraSettings
  | Common.Message.StorageInformation
  | Common.Message.CameraCaptureStatus
  | Common.Message.CameraImageCaptured
  | Common.Message.FlightInformation
  | Common.Message.MountOrientation
  | Common.Message.LoggingData
  | Common.Message.LoggingDataAcked
  | Common.Message.LoggingAck
  | Common.Message.VideoStreamInformation
  | Common.Message.VideoStreamStatus
  | Common.Message.CameraFovStatus
  | Common.Message.CameraTrackingImageStatus
  | Common.Message.CameraTrackingGeoStatus
  | Common.Message.GimbalManagerInformation
  | Common.Message.GimbalManagerStatus
  | Common.Message.GimbalManagerSetAttitude
  | Common.Message.GimbalDeviceInformation
  | Common.Message.GimbalDeviceSetAttitude
  | Common.Message.GimbalDeviceAttitudeStatus
  | Common.Message.AutopilotStateForGimbalDevice
  | Common.Message.GimbalManagerSetPitchyaw
  | Common.Message.GimbalManagerSetManualControl
  | Common.Message.EscInfo
  | Common.Message.EscStatus
  | Common.Message.WifiConfigAp
  | Common.Message.ProtocolVersion
  | Common.Message.AisVessel
  | Common.Message.UavcanNodeStatus
  | Common.Message.UavcanNodeInfo
  | Common.Message.ParamExtRequestRead
  | Common.Message.ParamExtRequestList
  | Common.Message.ParamExtValue
  | Common.Message.ParamExtSet
  | Common.Message.ParamExtAck
  | Common.Message.ObstacleDistance
  | Common.Message.Odometry
  | Common.Message.TrajectoryRepresentationWaypoints
  | Common.Message.TrajectoryRepresentationBezier
  | Common.Message.CellularStatus
  | Common.Message.IsbdLinkStatus
  | Common.Message.CellularConfig
  | Common.Message.RawRpm
  | Common.Message.UtmGlobalPosition
  | Common.Message.DebugFloatArray
  | Common.Message.OrbitExecutionStatus
  | Common.Message.SmartBatteryInfo
  | Common.Message.GeneratorStatus
  | Common.Message.ActuatorOutputStatus
  | Common.Message.TimeEstimateToTarget
  | Common.Message.Tunnel
  | Common.Message.CanFrame
  | Common.Message.CanfdFrame
  | Common.Message.CanFilterModify
  | Common.Message.OnboardComputerStatus
  | Common.Message.ComponentInformation
  | Common.Message.ComponentMetadata
  | Common.Message.PlayTuneV2
  | Common.Message.SupportedTunes
  | Common.Message.Event
  | Common.Message.CurrentEventSequence
  | Common.Message.RequestEvent
  | Common.Message.ResponseEventError
  | Common.Message.WheelDistance
  | Common.Message.WinchStatus
  | Common.Message.OpenDroneIdBasicId
  | Common.Message.OpenDroneIdLocation
  | Common.Message.OpenDroneIdAuthentication
  | Common.Message.OpenDroneIdSelfId
  | Common.Message.OpenDroneIdSystem
  | Common.Message.OpenDroneIdOperatorId
  | Common.Message.OpenDroneIdMessagePack
  | Common.Message.OpenDroneIdArmStatus
  | Common.Message.OpenDroneIdSystemUpdate
  | Common.Message.HygrometerSensor

A MAVLink message

@type mission_state() ::
  :mission_state_unknown
  | :mission_state_no_mission
  | :mission_state_not_started
  | :mission_state_active
  | :mission_state_paused
  | :mission_state_complete

States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles.

@type motor_test_order() ::
  :motor_test_order_default
  | :motor_test_order_sequence
  | :motor_test_order_board

Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST.

Link to this type

motor_test_throttle_type()

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

Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST.

Link to this type

nav_vtol_land_options()

View Source
@type nav_vtol_land_options() ::
  :nav_vtol_land_options_default
  | :nav_vtol_land_options_fw_descent
  | :nav_vtol_land_options_hover_descent
@type orbit_yaw_behaviour() ::
  :orbit_yaw_behaviour_hold_front_to_circle_center
  | :orbit_yaw_behaviour_hold_initial_heading
  | :orbit_yaw_behaviour_uncontrolled
  | :orbit_yaw_behaviour_hold_front_tangent_to_circle
  | :orbit_yaw_behaviour_rc_controlled

Yaw behaviour during orbit flight.

@type parachute_action() ::
  :parachute_disable | :parachute_enable | :parachute_release

Parachute actions. Trigger release and enable/disable auto-release.

@type param_ack() ::
  :param_ack_accepted
  | :param_ack_value_unsupported
  | :param_ack_failed
  | :param_ack_in_progress

Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).

Link to this type

position_target_typemask()

View Source
@type 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.

@type 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

preflight_storage_mission_action()

View Source
@type preflight_storage_mission_action() ::
  :mission_read_persistent | :mission_write_persistent | :mission_reset_default

Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

Link to this type

preflight_storage_parameter_action()

View Source
@type preflight_storage_parameter_action() ::
  :param_read_persistent
  | :param_write_persistent
  | :param_reset_config_default
  | :param_reset_sensor_default
  | :param_reset_all_default

Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

@type rc_type() :: :rc_type_spektrum_dsm2 | :rc_type_spektrum_dsmx

RC type

Link to this type

rtk_baseline_coordinate_system()

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

RTK GPS baseline coordinate system, used for RTK corrections

@type 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_serial0
  | :serial_control_serial1
  | :serial_control_serial2
  | :serial_control_serial3
  | :serial_control_serial4
  | :serial_control_serial5
  | :serial_control_serial6
  | :serial_control_serial7
  | :serial_control_serial8
  | :serial_control_serial9

SERIAL_CONTROL device types

@type 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)

@type set_focus_type() ::
  :focus_type_step
  | :focus_type_continuous
  | :focus_type_range
  | :focus_type_meters
  | :focus_type_auto
  | :focus_type_auto_single
  | :focus_type_auto_continuous

Focus types for MAV_CMD_SET_CAMERA_FOCUS

@type storage_status() ::
  :storage_status_empty
  | :storage_status_unformatted
  | :storage_status_ready
  | :storage_status_not_supported

Flags to indicate the status of camera storage.

@type storage_type() ::
  :storage_type_unknown
  | :storage_type_usb_stick
  | :storage_type_sd
  | :storage_type_microsd
  | :storage_type_cf
  | :storage_type_cfe
  | :storage_type_xqd
  | :storage_type_hd
  | :storage_type_other

Flags to indicate the type of storage.

@type storage_usage_flag() ::
  :storage_usage_flag_set
  | :storage_usage_flag_photo
  | :storage_usage_flag_video
  | :storage_usage_flag_logs

Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).

@type tune_format() :: :tune_format_qbasic1_1 | :tune_format_mml_modern

Tune formats (used for vehicle buzzer/tone generation).

@type uavcan_node_health() ::
  :uavcan_node_health_ok
  | :uavcan_node_health_warning
  | :uavcan_node_health_error
  | :uavcan_node_health_critical

Generalized UAVCAN node health

@type 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

utm_data_avail_flags()

View Source
@type utm_data_avail_flags() ::
  :utm_data_avail_flags_time_valid
  | :utm_data_avail_flags_uas_id_available
  | :utm_data_avail_flags_position_available
  | :utm_data_avail_flags_altitude_available
  | :utm_data_avail_flags_relative_altitude_available
  | :utm_data_avail_flags_horizontal_velo_available
  | :utm_data_avail_flags_vertical_velo_available
  | :utm_data_avail_flags_next_waypoint_available

Flags for the global position report.

@type utm_flight_state() ::
  :utm_flight_state_unknown
  | :utm_flight_state_ground
  | :utm_flight_state_airborne
  | :utm_flight_state_emergency
  | :utm_flight_state_noctrl

Airborne status of UAS.

Link to this type

video_stream_status_flags()

View Source
@type video_stream_status_flags() ::
  :video_stream_status_flags_running | :video_stream_status_flags_thermal

Stream status flags (Bitmap)

@type video_stream_type() ::
  :video_stream_type_rtsp
  | :video_stream_type_rtpudp
  | :video_stream_type_tcp_mpeg
  | :video_stream_type_mpeg_ts_h264

Video stream types

Link to this type

vtol_transition_heading()

View Source
@type 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

@type wifi_config_ap_mode() ::
  :wifi_config_ap_mode_undefined
  | :wifi_config_ap_mode_ap
  | :wifi_config_ap_mode_station
  | :wifi_config_ap_mode_disabled

WiFi Mode.

Link to this type

wifi_config_ap_response()

View Source
@type wifi_config_ap_response() ::
  :wifi_config_ap_response_undefined
  | :wifi_config_ap_response_accepted
  | :wifi_config_ap_response_rejected
  | :wifi_config_ap_response_mode_error
  | :wifi_config_ap_response_ssid_error
  | :wifi_config_ap_response_password_error

Possible responses from a WIFI_CONFIG_AP message.

@type winch_actions() ::
  :winch_relaxed
  | :winch_relative_length_control
  | :winch_rate_control
  | :winch_lock
  | :winch_deliver
  | :winch_hold
  | :winch_retract
  | :winch_load_line
  | :winch_abandon_line
  | :winch_load_payload

Winch actions.