dialects/matrixpilot
library
Classes
-
ActuatorControlTarget
-
Set the vehicle attitude and body angular rates.
-
ActuatorOutputStatus
-
The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.
-
AdsbVehicle
-
The location and information of an ADSB vehicle
-
Airspeeds
-
The airspeed measured by sensors and IMU
-
AisVessel
-
The location and information of an AIS vessel
-
Altitude
-
The current system altitude.
-
Altitudes
-
The altitude measured by sensors and IMU
-
Attitude
-
The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic).
-
AttitudeQuaternion
-
The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).
-
AttitudeQuaternionCov
-
The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).
-
AttitudeTarget
-
Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way.
-
AttPosMocap
-
Motion capture attitude and position
-
AuthKey
-
Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.
-
AutopilotStateForGimbalDevice
-
Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis.
-
AutopilotVersion
-
Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE.
-
BatteryInfo
-
Battery information that is static, or requires infrequent update.
This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate.
BATTERY_STATUS_V2 is used for higher-rate battery status information.
-
BatteryStatus
-
Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO.
-
ButtonChange
-
Report button state change.
-
CameraCaptureStatus
-
Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.
-
CameraFovStatus
-
Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.
-
CameraImageCaptured
-
Information about a captured image. This is emitted every time a message is captured.
MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers:
MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers.
MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send:
set to 0 (default) to send just the the message for the sequence number in param 2,
set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers,
set to the sequence number of the final message in the range.
-
CameraInformation
-
Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.
-
CameraSettings
-
Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.
-
CameraTrackingGeoStatus
-
Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.
-
CameraTrackingImageStatus
-
Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.
-
CameraTrigger
-
Camera-IMU triggering and synchronisation message.
-
CanfdFrame
-
A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)
-
CanFilterModify
-
Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.
-
CanFrame
-
A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD.
-
CellularConfig
-
Configure cellular modems.
This message is re-emitted as an acknowledgement by the modem.
The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE.
-
CellularStatus
-
Report current used cellular network status
-
ChangeOperatorControl
-
Request to control this MAV
-
ChangeOperatorControlAck
-
Accept / deny control of this MAV
-
Collision
-
Information about a potential collision
-
CommandAck
-
Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html
-
CommandCancel
-
Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html
-
CommandInt
-
Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html
-
CommandLong
-
Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html
-
ComponentInformation
-
Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE.
-
ComponentMetadata
-
Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE.
-
ControlSystemState
-
The smoothed, monotonic system state used to feed the control loops of the system.
-
CurrentEventSequence
-
Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events.
-
DataStream
-
Data stream status information.
-
DataTransmissionHandshake
-
Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.
-
Debug
-
Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.
-
DebugFloatArray
-
Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code.
-
DebugVect
-
To debug something using a named 3D vector.
-
DistanceSensor
-
Distance sensor information for an onboard rangefinder.
-
EfiStatus
-
EFI status output
-
EncapsulatedData
-
Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.
-
EscInfo
-
ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data.
-
EscStatus
-
ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer).
-
EstimatorStatus
-
Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user.
-
Event
-
Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component).
-
ExtendedSysState
-
Provides state for additional features
-
FenceStatus
-
Status of geo-fencing. Sent in extended status stream when fencing enabled.
-
FileTransferProtocol
-
File transfer protocol message: https://mavlink.io/en/services/ftp.html.
-
FlexifunctionBufferFunction
-
Flexifunction type and parameters for component at function index from buffer
-
FlexifunctionBufferFunctionAck
-
Flexifunction type and parameters for component at function index from buffer
-
FlexifunctionCommand
-
Acknowldge success or failure of a flexifunction command
-
FlexifunctionCommandAck
-
Acknowldge success or failure of a flexifunction command
-
FlexifunctionDirectory
-
Acknowldge success or failure of a flexifunction command
-
FlexifunctionDirectoryAck
-
Acknowldge success or failure of a flexifunction command
-
FlexifunctionReadReq
-
Request reading of flexifunction data
-
FlexifunctionSet
-
Depreciated but used as a compiler flag. Do not remove
-
FlightInformation
-
Flight information.
This includes time since boot for arm, takeoff, and land, and a flight number.
Takeoff and landing values reset to zero on arm.
This can be requested using MAV_CMD_REQUEST_MESSAGE.
Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number.
-
FollowTarget
-
Current motion information from a designated system
-
GeneratorStatus
-
Telemetry of power generation system. Alternator or mechanical generator.
-
GimbalDeviceAttitudeStatus
-
Message reporting the status of a gimbal device.
This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz).
For the angles encoded in the quaternion and the angular velocities holds:
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame).
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame).
If neither of these flags are set, then (for backwards compatibility) it holds:
If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame),
else they are relative to the vehicle heading (vehicle frame).
Other conditions of the flags are not allowed.
The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as
q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN).
If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set,
then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored.
New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME,
and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN.
-
GimbalDeviceInformation
-
Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc..
-
GimbalDeviceSetAttitude
-
Low level message to control a gimbal device's attitude.
This message is to be sent from the gimbal manager to the gimbal device component.
The quaternion and angular velocities can be set to NaN according to use case.
For the angles encoded in the quaternion and the angular velocities holds:
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame).
If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame).
If neither of these flags are set, then (for backwards compatibility) it holds:
If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame),
else they are relative to the vehicle heading (vehicle frame).
Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed.
These rules are to ensure backwards compatibility.
New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.
-
GimbalManagerInformation
-
Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE.
-
GimbalManagerSetAttitude
-
High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.
-
GimbalManagerSetManualControl
-
High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.
-
GimbalManagerSetPitchyaw
-
Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation.
-
GimbalManagerStatus
-
Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz).
-
GlobalPositionInt
-
The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It
is designed as scaled integer message since the resolution of float is not sufficient.
-
GlobalPositionIntCov
-
The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.
-
GlobalVisionPositionEstimate
-
Global position/attitude estimate from a vision source.
-
Gps2Raw
-
Second GPS data.
-
Gps2Rtk
-
RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting
-
GpsGlobalOrigin
-
Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.
-
GpsInjectData
-
Data for injecting into the onboard GPS (used for DGPS)
-
GpsInput
-
GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system.
-
GpsRawInt
-
The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.
-
GpsRtcmData
-
RTCM message for injecting into the onboard GPS (used for DGPS)
-
GpsRtk
-
RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting
-
GpsStatus
-
The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites.
-
Heartbeat
-
The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html
-
HighLatency
-
Message appropriate for high latency connections like Iridium
-
HighLatency2
-
Message appropriate for high latency connections like Iridium (version 2)
-
HighresImu
-
The IMU readings in SI units in NED body frame
-
HilActuatorControls
-
Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)
-
HilControls
-
Sent from autopilot to simulation. Hardware in the loop control outputs
-
HilGps
-
The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.
-
HilOpticalFlow
-
Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)
-
HilRcInputsRaw
-
Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
-
HilSensor
-
The IMU readings in SI units in NED body frame
-
HilState
-
Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.
-
HilStateQuaternion
-
Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.
-
HomePosition
-
Contains the home position.
The home position is the default position that the system will return to and land on.
The position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME.
The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface.
Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach.
The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.
Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command).
-
HygrometerSensor
-
Temperature and humidity from hygrometer.
-
IsbdLinkStatus
-
Status of the Iridium SBD link.
-
LandingTarget
-
The location of a landing target. See: https://mavlink.io/en/services/landing_target.html
-
LinkNodeStatus
-
Status generated in each node in the communication chain and injected into MAVLink stream.
-
LocalPositionNed
-
The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
-
LocalPositionNedCov
-
The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
-
LocalPositionNedSystemGlobalOffset
-
The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
-
LogData
-
Reply to LOG_REQUEST_DATA
-
LogEntry
-
Reply to LOG_REQUEST_LIST
-
LogErase
-
Erase all logs
-
LoggingAck
-
An ack for a LOGGING_DATA_ACKED message
-
LoggingData
-
A message containing logged data (see also MAV_CMD_LOGGING_START)
-
LoggingDataAcked
-
A message containing logged data which requires a LOGGING_ACK to be sent back
-
LogRequestData
-
Request a chunk of a log
-
LogRequestEnd
-
Stop log transfer and resume normal logging
-
LogRequestList
-
Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0.
-
MagCalReport
-
Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.
-
ManualControl
-
This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask
-
ManualSetpoint
-
Setpoint in roll, pitch, yaw and thrust from the operator
-
MavlinkDialectMatrixpilot
-
-
MemoryVect
-
Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
-
MessageInterval
-
The interval between messages for a particular MAVLink message ID.
This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required).
It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL.
This interface replaces DATA_STREAM.
-
MissionAck
-
Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).
-
MissionClearAll
-
Delete all mission items at once.
-
MissionCount
-
This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints.
-
MissionCurrent
-
Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running).
This message should be streamed all the time (nominally at 1Hz).
This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT.
-
MissionItem
-
Message encoding a mission item. This message is emitted to announce
the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.
-
MissionItemInt
-
Message encoding a mission item. This message is emitted to announce
the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.
-
MissionItemReached
-
A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.
-
MissionRequest
-
Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html
-
MissionRequestInt
-
Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html
-
MissionRequestList
-
Request the overall list of mission items from the system/component.
-
MissionRequestPartialList
-
Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint.
-
MissionSetCurrent
-
Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed).
If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items.
Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2).
-
MissionWritePartialList
-
This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!
-
MountOrientation
-
Orientation of a mount
-
NamedValueFloat
-
Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
-
NamedValueInt
-
Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
-
NavControllerOutput
-
The state of the navigation and position controller.
-
ObstacleDistance
-
Obstacle distances in front of the sensor, starting from the left in increment degrees to the right
-
Odometry
-
Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html).
-
OnboardComputerStatus
-
Hardware status sent by an onboard computer.
-
OpenDroneIdArmStatus
-
Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm.
-
OpenDroneIdAuthentication
-
Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes.
-
OpenDroneIdBasicId
-
Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html.
-
OpenDroneIdLocation
-
Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft.
-
OpenDroneIdMessagePack
-
An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon.
-
OpenDroneIdOperatorId
-
Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID.
-
OpenDroneIdSelfId
-
Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation.
-
OpenDroneIdSystem
-
Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information.
-
OpenDroneIdSystemUpdate
-
Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location.
-
OpticalFlow
-
Optical flow from a flow sensor (e.g. optical mouse sensor)
-
OpticalFlowRad
-
Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)
-
OrbitExecutionStatus
-
Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT).
-
ParamExtAck
-
Response from a PARAM_EXT_SET message.
-
ParamExtRequestList
-
Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE.
-
ParamExtRequestRead
-
Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response.
-
ParamExtSet
-
Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response.
-
ParamExtValue
-
Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout.
-
ParamMapRc
-
Bind a RC channel to a parameter. The parameter should change according to the RC channel value.
-
ParamRequestList
-
Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html
-
ParamRequestRead
-
Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key
const char*
-> valuefloat. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code.
-
ParamSet
-
Set a parameter value (write new value to permanent storage).
The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html.
PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received.
-
ParamValue
-
Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html
-
Ping
-
A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html
-
PlayTune
-
Control vehicle tone generation (buzzer).
-
PlayTuneV2
-
Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE.
-
PositionTargetGlobalInt
-
Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.
-
PositionTargetLocalNed
-
Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way.
-
PowerStatus
-
Power supply status
-
ProtocolVersion
-
Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly.
-
RadioStatus
-
Status generated by radio and injected into MAVLink stream.
-
RawImu
-
The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging.
-
RawPressure
-
The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.
-
RawRpm
-
RPM sensor data message.
-
RcChannels
-
The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.
-
RcChannelsOverride
-
The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels
-
RcChannelsRaw
-
The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.
-
RcChannelsScaled
-
The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX.
-
RequestDataStream
-
Request a data stream.
-
RequestEvent
-
Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response.
-
ResourceRequest
-
The autopilot is requesting a resource (file, binary, other type of data)
-
ResponseEventError
-
Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore).
-
SafetyAllowedArea
-
Read out the safety zone the MAV currently assumes.
-
SafetySetAllowedArea
-
Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.
-
ScaledImu
-
The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units
-
ScaledImu2
-
The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units
-
ScaledImu3
-
The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units
-
ScaledPressure
-
The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.
-
ScaledPressure2
-
Barometer readings for 2nd barometer
-
ScaledPressure3
-
Barometer readings for 3rd barometer
-
SerialControl
-
Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate.
-
Backwards compatible version of SERIAL_UDB_EXTRA F13: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F14: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F15 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F16 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F17 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F18 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F19 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F20 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F21 format
-
Backwards compatible version of SERIAL_UDB_EXTRA F22 format
-
Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A
-
Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B
-
Backwards compatible version of SERIAL_UDB_EXTRA F4: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F5: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F6: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F7: format
-
Backwards compatible version of SERIAL_UDB_EXTRA F8: format
-
ServoOutputRaw
-
Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.
-
SetActuatorControlTarget
-
Set the vehicle attitude and body angular rates.
-
SetAttitudeTarget
-
Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system).
-
SetGpsGlobalOrigin
-
Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.
-
SetHomePosition
-
Sets the home position.
The home position is the default position that the system will return to and land on.
The position is set automatically by the system during the takeoff (and may also be set using this message).
The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface.
Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach.
The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.
Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
-
SetMode
-
Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.
-
SetPositionTargetGlobalInt
-
Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system).
-
SetPositionTargetLocalNed
-
Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system).
-
SetupSigning
-
Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing
-
SimState
-
Status of simulation environment, if used
-
Statustext
-
Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).
-
StorageInformation
-
Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc.
-
SupportedTunes
-
Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE.
-
SysStatus
-
The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.
-
SystemTime
-
The system time is the time of the master clock, typically the computer clock of the main onboard computer.
-
TerrainCheck
-
Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission.
-
TerrainData
-
Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html
-
TerrainReport
-
Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html
-
TerrainRequest
-
Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html
-
TimeEstimateToTarget
-
Time/duration estimates for various events and actions given the current vehicle state and position.
-
Timesync
-
Time synchronization message.
The message is used for both timesync requests and responses.
The request is sent with
ts1=syncing component timestamp
and tc1=0
, and may be broadcast or targeted to a specific system/component.
The response is sent with ts1=syncing component timestamp
(mirror back unchanged), and tc1=responding component timestamp
, with the target_system
and target_component
set to ids of the original request.
Systems can determine if they are receiving a request or response based on the value of tc
.
If the response has target_system==target_component==0
the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error.
Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used).
The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset.
-
TrajectoryRepresentationBezier
-
Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED).
-
TrajectoryRepresentationWaypoints
-
Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED).
-
Tunnel
-
Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification.
-
UavcanNodeInfo
-
General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service "uavcan.protocol.GetNodeInfo" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org.
-
UavcanNodeStatus
-
General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message "uavcan.protocol.NodeStatus" for the background information. The UAVCAN specification is available at http://uavcan.org.
-
UtmGlobalPosition
-
The global position resulting from GPS and sensor fusion.
-
V2Extension
-
Message implementing parts of the V2 payload specs in V1 frames for transitional support.
-
VfrHud
-
Metrics typically displayed on a HUD for fixed wing aircraft.
-
Vibration
-
Vibration levels and accelerometer clipping
-
ViconPositionEstimate
-
Global position estimate from a Vicon motion system source.
-
VideoStreamInformation
-
Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc.
-
VideoStreamStatus
-
Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE.
-
VisionPositionEstimate
-
Local position/attitude estimate from a vision source.
-
VisionSpeedEstimate
-
Speed estimate from a vision source.
-
WheelDistance
-
Cumulative distance traveled for each reported wheel.
-
WifiConfigAp
-
Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE
-
WinchStatus
-
Winch status.
-
WindCov
-
Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD).
Constants
-
actuatorConfiguration3dModeOff
→ const ActuatorConfiguration
-
Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust).
-
actuatorConfiguration3dModeOn
→ const ActuatorConfiguration
-
Permanently set the actuator (ESC) to 3D mode (reversible thrust).
-
actuatorConfigurationBeep
→ const ActuatorConfiguration
-
Command the actuator to beep now.
-
actuatorConfigurationNone
→ const ActuatorConfiguration
-
Do nothing.
-
actuatorConfigurationSpinDirection1
→ const ActuatorConfiguration
-
Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise).
-
actuatorConfigurationSpinDirection2
→ const ActuatorConfiguration
-
Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1).
-
actuatorOutputFunctionMotor1
→ const ActuatorOutputFunction
-
Motor 1
-
actuatorOutputFunctionMotor10
→ const ActuatorOutputFunction
-
Motor 10
-
actuatorOutputFunctionMotor11
→ const ActuatorOutputFunction
-
Motor 11
-
actuatorOutputFunctionMotor12
→ const ActuatorOutputFunction
-
Motor 12
-
actuatorOutputFunctionMotor13
→ const ActuatorOutputFunction
-
Motor 13
-
actuatorOutputFunctionMotor14
→ const ActuatorOutputFunction
-
Motor 14
-
actuatorOutputFunctionMotor15
→ const ActuatorOutputFunction
-
Motor 15
-
actuatorOutputFunctionMotor16
→ const ActuatorOutputFunction
-
Motor 16
-
actuatorOutputFunctionMotor2
→ const ActuatorOutputFunction
-
Motor 2
-
actuatorOutputFunctionMotor3
→ const ActuatorOutputFunction
-
Motor 3
-
actuatorOutputFunctionMotor4
→ const ActuatorOutputFunction
-
Motor 4
-
actuatorOutputFunctionMotor5
→ const ActuatorOutputFunction
-
Motor 5
-
actuatorOutputFunctionMotor6
→ const ActuatorOutputFunction
-
Motor 6
-
actuatorOutputFunctionMotor7
→ const ActuatorOutputFunction
-
Motor 7
-
actuatorOutputFunctionMotor8
→ const ActuatorOutputFunction
-
Motor 8
-
actuatorOutputFunctionMotor9
→ const ActuatorOutputFunction
-
Motor 9
-
actuatorOutputFunctionNone
→ const ActuatorOutputFunction
-
No function (disabled).
-
actuatorOutputFunctionServo1
→ const ActuatorOutputFunction
-
Servo 1
-
actuatorOutputFunctionServo10
→ const ActuatorOutputFunction
-
Servo 10
-
actuatorOutputFunctionServo11
→ const ActuatorOutputFunction
-
Servo 11
-
actuatorOutputFunctionServo12
→ const ActuatorOutputFunction
-
Servo 12
-
actuatorOutputFunctionServo13
→ const ActuatorOutputFunction
-
Servo 13
-
actuatorOutputFunctionServo14
→ const ActuatorOutputFunction
-
Servo 14
-
actuatorOutputFunctionServo15
→ const ActuatorOutputFunction
-
Servo 15
-
actuatorOutputFunctionServo16
→ const ActuatorOutputFunction
-
Servo 16
-
actuatorOutputFunctionServo2
→ const ActuatorOutputFunction
-
Servo 2
-
actuatorOutputFunctionServo3
→ const ActuatorOutputFunction
-
Servo 3
-
actuatorOutputFunctionServo4
→ const ActuatorOutputFunction
-
Servo 4
-
actuatorOutputFunctionServo5
→ const ActuatorOutputFunction
-
Servo 5
-
actuatorOutputFunctionServo6
→ const ActuatorOutputFunction
-
Servo 6
-
actuatorOutputFunctionServo7
→ const ActuatorOutputFunction
-
Servo 7
-
actuatorOutputFunctionServo8
→ const ActuatorOutputFunction
-
Servo 8
-
actuatorOutputFunctionServo9
→ const ActuatorOutputFunction
-
Servo 9
-
adsbAltitudeTypeGeometric
→ const AdsbAltitudeType
-
Altitude reported from a GNSS source
-
adsbAltitudeTypePressureQnh
→ const AdsbAltitudeType
-
Altitude reported from a Baro source using QNH reference
-
adsbEmitterTypeEmergencySurface
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_EMERGENCY_SURFACE
-
adsbEmitterTypeGlider
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_GLIDER
-
adsbEmitterTypeHeavy
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_HEAVY
-
adsbEmitterTypeHighlyManuv
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_HIGHLY_MANUV
-
adsbEmitterTypeHighVortexLarge
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE
-
adsbEmitterTypeLarge
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_LARGE
-
adsbEmitterTypeLight
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_LIGHT
-
adsbEmitterTypeLighterAir
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_LIGHTER_AIR
-
adsbEmitterTypeNoInfo
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_NO_INFO
-
adsbEmitterTypeParachute
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_PARACHUTE
-
adsbEmitterTypePointObstacle
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_POINT_OBSTACLE
-
adsbEmitterTypeRotocraft
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_ROTOCRAFT
-
adsbEmitterTypeServiceSurface
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_SERVICE_SURFACE
-
adsbEmitterTypeSmall
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_SMALL
-
adsbEmitterTypeSpace
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_SPACE
-
adsbEmitterTypeUav
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_UAV
-
adsbEmitterTypeUltraLight
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_ULTRA_LIGHT
-
adsbEmitterTypeUnassgined3
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_UNASSGINED3
-
adsbEmitterTypeUnassigned
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_UNASSIGNED
-
adsbEmitterTypeUnassigned2
→ const AdsbEmitterType
-
ADSB_EMITTER_TYPE_UNASSIGNED2
-
adsbFlagsBaroValid
→ const AdsbFlags
-
ADSB_FLAGS_BARO_VALID
-
adsbFlagsSimulated
→ const AdsbFlags
-
ADSB_FLAGS_SIMULATED
-
adsbFlagsSourceUat
→ const AdsbFlags
-
ADSB_FLAGS_SOURCE_UAT
-
adsbFlagsValidAltitude
→ const AdsbFlags
-
ADSB_FLAGS_VALID_ALTITUDE
-
adsbFlagsValidCallsign
→ const AdsbFlags
-
ADSB_FLAGS_VALID_CALLSIGN
-
adsbFlagsValidCoords
→ const AdsbFlags
-
ADSB_FLAGS_VALID_COORDS
-
adsbFlagsValidHeading
→ const AdsbFlags
-
ADSB_FLAGS_VALID_HEADING
-
adsbFlagsValidSquawk
→ const AdsbFlags
-
ADSB_FLAGS_VALID_SQUAWK
-
adsbFlagsValidVelocity
→ const AdsbFlags
-
ADSB_FLAGS_VALID_VELOCITY
-
adsbFlagsVerticalVelocityValid
→ const AdsbFlags
-
ADSB_FLAGS_VERTICAL_VELOCITY_VALID
-
aisFlagsHighVelocity
→ const AisFlags
-
1 = Velocity over 52.5765m/s (102.2 knots)
-
aisFlagsLargeBowDimension
→ const AisFlags
-
Distance to bow is larger than 511m
-
aisFlagsLargePortDimension
→ const AisFlags
-
Distance to port side is larger than 63m
-
aisFlagsLargeStarboardDimension
→ const AisFlags
-
Distance to starboard side is larger than 63m
-
aisFlagsLargeSternDimension
→ const AisFlags
-
Distance to stern is larger than 511m
-
aisFlagsPositionAccuracy
→ const AisFlags
-
1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m.
-
aisFlagsTurnRateSignOnly
→ const AisFlags
-
Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s
-
aisFlagsValidCallsign
→ const AisFlags
-
AIS_FLAGS_VALID_CALLSIGN
-
aisFlagsValidCog
→ const AisFlags
-
AIS_FLAGS_VALID_COG
-
aisFlagsValidDimensions
→ const AisFlags
-
AIS_FLAGS_VALID_DIMENSIONS
-
aisFlagsValidName
→ const AisFlags
-
AIS_FLAGS_VALID_NAME
-
aisFlagsValidTurnRate
→ const AisFlags
-
AIS_FLAGS_VALID_TURN_RATE
-
aisFlagsValidVelocity
→ const AisFlags
-
AIS_FLAGS_VALID_VELOCITY
-
aisNavAground
→ const AisNavStatus
-
AIS_NAV_AGROUND
-
aisNavAisSart
→ const AisNavStatus
-
Search And Rescue Transponder.
-
aisNavAnchored
→ const AisNavStatus
-
AIS_NAV_ANCHORED
-
aisNavDraughtConstrained
→ const AisNavStatus
-
AIS_NAV_DRAUGHT_CONSTRAINED
-
aisNavFishing
→ const AisNavStatus
-
AIS_NAV_FISHING
-
aisNavMoored
→ const AisNavStatus
-
AIS_NAV_MOORED
-
aisNavReserved1
→ const AisNavStatus
-
AIS_NAV_RESERVED_1
-
aisNavReserved2
→ const AisNavStatus
-
AIS_NAV_RESERVED_2
-
aisNavReserved3
→ const AisNavStatus
-
AIS_NAV_RESERVED_3
-
aisNavReservedHsc
→ const AisNavStatus
-
AIS_NAV_RESERVED_HSC
-
aisNavReservedWig
→ const AisNavStatus
-
AIS_NAV_RESERVED_WIG
-
aisNavRestrictedManoeuverability
→ const AisNavStatus
-
AIS_NAV_RESTRICTED_MANOEUVERABILITY
-
aisNavSailing
→ const AisNavStatus
-
AIS_NAV_SAILING
-
aisNavUnCommanded
→ const AisNavStatus
-
AIS_NAV_UN_COMMANDED
-
aisNavUnknown
→ const AisNavStatus
-
Not available (default).
-
aisTypeAntiPollution
→ const AisType
-
Anti-pollution equipment.
-
aisTypeCargo
→ const AisType
-
AIS_TYPE_CARGO
-
aisTypeCargoHazardousA
→ const AisType
-
AIS_TYPE_CARGO_HAZARDOUS_A
-
aisTypeCargoHazardousB
→ const AisType
-
AIS_TYPE_CARGO_HAZARDOUS_B
-
aisTypeCargoHazardousC
→ const AisType
-
AIS_TYPE_CARGO_HAZARDOUS_C
-
aisTypeCargoHazardousD
→ const AisType
-
AIS_TYPE_CARGO_HAZARDOUS_D
-
aisTypeCargoReserved1
→ const AisType
-
AIS_TYPE_CARGO_RESERVED_1
-
aisTypeCargoReserved2
→ const AisType
-
AIS_TYPE_CARGO_RESERVED_2
-
aisTypeCargoReserved3
→ const AisType
-
AIS_TYPE_CARGO_RESERVED_3
-
aisTypeCargoReserved4
→ const AisType
-
AIS_TYPE_CARGO_RESERVED_4
-
aisTypeCargoUnknown
→ const AisType
-
AIS_TYPE_CARGO_UNKNOWN
-
aisTypeDiving
→ const AisType
-
AIS_TYPE_DIVING
-
aisTypeDredging
→ const AisType
-
Dredging or other underwater ops.
-
aisTypeFishing
→ const AisType
-
AIS_TYPE_FISHING
-
aisTypeHsc
→ const AisType
-
High Speed Craft.
-
aisTypeHscHazardousA
→ const AisType
-
AIS_TYPE_HSC_HAZARDOUS_A
-
aisTypeHscHazardousB
→ const AisType
-
AIS_TYPE_HSC_HAZARDOUS_B
-
aisTypeHscHazardousC
→ const AisType
-
AIS_TYPE_HSC_HAZARDOUS_C
-
aisTypeHscHazardousD
→ const AisType
-
AIS_TYPE_HSC_HAZARDOUS_D
-
aisTypeHscReserved1
→ const AisType
-
AIS_TYPE_HSC_RESERVED_1
-
aisTypeHscReserved2
→ const AisType
-
AIS_TYPE_HSC_RESERVED_2
-
aisTypeHscReserved3
→ const AisType
-
AIS_TYPE_HSC_RESERVED_3
-
aisTypeHscReserved4
→ const AisType
-
AIS_TYPE_HSC_RESERVED_4
-
aisTypeHscUnknown
→ const AisType
-
AIS_TYPE_HSC_UNKNOWN
-
aisTypeLawEnforcement
→ const AisType
-
AIS_TYPE_LAW_ENFORCEMENT
-
aisTypeMedicalTransport
→ const AisType
-
AIS_TYPE_MEDICAL_TRANSPORT
-
aisTypeMilitary
→ const AisType
-
AIS_TYPE_MILITARY
-
aisTypeNonecombatant
→ const AisType
-
Noncombatant ship according to RR Resolution No. 18.
-
aisTypeOther
→ const AisType
-
AIS_TYPE_OTHER
-
aisTypeOtherHazardousA
→ const AisType
-
AIS_TYPE_OTHER_HAZARDOUS_A
-
aisTypeOtherHazardousB
→ const AisType
-
AIS_TYPE_OTHER_HAZARDOUS_B
-
aisTypeOtherHazardousC
→ const AisType
-
AIS_TYPE_OTHER_HAZARDOUS_C
-
aisTypeOtherHazardousD
→ const AisType
-
AIS_TYPE_OTHER_HAZARDOUS_D
-
aisTypeOtherReserved1
→ const AisType
-
AIS_TYPE_OTHER_RESERVED_1
-
aisTypeOtherReserved2
→ const AisType
-
AIS_TYPE_OTHER_RESERVED_2
-
aisTypeOtherReserved3
→ const AisType
-
AIS_TYPE_OTHER_RESERVED_3
-
aisTypeOtherReserved4
→ const AisType
-
AIS_TYPE_OTHER_RESERVED_4
-
aisTypeOtherUnknown
→ const AisType
-
AIS_TYPE_OTHER_UNKNOWN
-
aisTypePassenger
→ const AisType
-
AIS_TYPE_PASSENGER
-
aisTypePassengerHazardousA
→ const AisType
-
AIS_TYPE_PASSENGER_HAZARDOUS_A
-
aisTypePassengerHazardousB
→ const AisType
-
AIS_TYPE_PASSENGER_HAZARDOUS_B
-
aisTypePassengerHazardousC
→ const AisType
-
AIS_TYPE_PASSENGER_HAZARDOUS_C
-
aisTypePassengerHazardousD
→ const AisType
-
AIS_TYPE_PASSENGER_HAZARDOUS_D
-
aisTypePassengerReserved1
→ const AisType
-
AIS_TYPE_PASSENGER_RESERVED_1
-
aisTypePassengerReserved2
→ const AisType
-
AIS_TYPE_PASSENGER_RESERVED_2
-
aisTypePassengerReserved3
→ const AisType
-
AIS_TYPE_PASSENGER_RESERVED_3
-
aisTypePassengerReserved4
→ const AisType
-
AIS_TYPE_PASSENGER_RESERVED_4
-
aisTypePassengerUnknown
→ const AisType
-
AIS_TYPE_PASSENGER_UNKNOWN
-
aisTypePilot
→ const AisType
-
AIS_TYPE_PILOT
-
aisTypePleasure
→ const AisType
-
AIS_TYPE_PLEASURE
-
aisTypePortTender
→ const AisType
-
AIS_TYPE_PORT_TENDER
-
aisTypeReserved1
→ const AisType
-
AIS_TYPE_RESERVED_1
-
aisTypeReserved10
→ const AisType
-
AIS_TYPE_RESERVED_10
-
aisTypeReserved11
→ const AisType
-
AIS_TYPE_RESERVED_11
-
aisTypeReserved12
→ const AisType
-
AIS_TYPE_RESERVED_12
-
aisTypeReserved13
→ const AisType
-
AIS_TYPE_RESERVED_13
-
aisTypeReserved14
→ const AisType
-
AIS_TYPE_RESERVED_14
-
aisTypeReserved15
→ const AisType
-
AIS_TYPE_RESERVED_15
-
aisTypeReserved16
→ const AisType
-
AIS_TYPE_RESERVED_16
-
aisTypeReserved17
→ const AisType
-
AIS_TYPE_RESERVED_17
-
aisTypeReserved18
→ const AisType
-
AIS_TYPE_RESERVED_18
-
aisTypeReserved19
→ const AisType
-
AIS_TYPE_RESERVED_19
-
aisTypeReserved2
→ const AisType
-
AIS_TYPE_RESERVED_2
-
aisTypeReserved20
→ const AisType
-
AIS_TYPE_RESERVED_20
-
aisTypeReserved21
→ const AisType
-
AIS_TYPE_RESERVED_21
-
aisTypeReserved3
→ const AisType
-
AIS_TYPE_RESERVED_3
-
aisTypeReserved4
→ const AisType
-
AIS_TYPE_RESERVED_4
-
aisTypeReserved5
→ const AisType
-
AIS_TYPE_RESERVED_5
-
aisTypeReserved6
→ const AisType
-
AIS_TYPE_RESERVED_6
-
aisTypeReserved7
→ const AisType
-
AIS_TYPE_RESERVED_7
-
aisTypeReserved8
→ const AisType
-
AIS_TYPE_RESERVED_8
-
aisTypeReserved9
→ const AisType
-
AIS_TYPE_RESERVED_9
-
aisTypeSailing
→ const AisType
-
AIS_TYPE_SAILING
-
aisTypeSar
→ const AisType
-
Search And Rescue vessel.
-
aisTypeSpareLocal1
→ const AisType
-
AIS_TYPE_SPARE_LOCAL_1
-
aisTypeSpareLocal2
→ const AisType
-
AIS_TYPE_SPARE_LOCAL_2
-
aisTypeTanker
→ const AisType
-
AIS_TYPE_TANKER
-
aisTypeTankerHazardousA
→ const AisType
-
AIS_TYPE_TANKER_HAZARDOUS_A
-
aisTypeTankerHazardousB
→ const AisType
-
AIS_TYPE_TANKER_HAZARDOUS_B
-
aisTypeTankerHazardousC
→ const AisType
-
AIS_TYPE_TANKER_HAZARDOUS_C
-
aisTypeTankerHazardousD
→ const AisType
-
AIS_TYPE_TANKER_HAZARDOUS_D
-
aisTypeTankerReserved1
→ const AisType
-
AIS_TYPE_TANKER_RESERVED_1
-
aisTypeTankerReserved2
→ const AisType
-
AIS_TYPE_TANKER_RESERVED_2
-
aisTypeTankerReserved3
→ const AisType
-
AIS_TYPE_TANKER_RESERVED_3
-
aisTypeTankerReserved4
→ const AisType
-
AIS_TYPE_TANKER_RESERVED_4
-
aisTypeTankerUnknown
→ const AisType
-
AIS_TYPE_TANKER_UNKNOWN
-
aisTypeTowing
→ const AisType
-
AIS_TYPE_TOWING
-
aisTypeTowingLarge
→ const AisType
-
Towing: length exceeds 200m or breadth exceeds 25m.
-
aisTypeTug
→ const AisType
-
AIS_TYPE_TUG
-
aisTypeUnknown
→ const AisType
-
Not available (default).
-
aisTypeWig
→ const AisType
-
Wing In Ground effect.
-
aisTypeWigHazardousA
→ const AisType
-
AIS_TYPE_WIG_HAZARDOUS_A
-
aisTypeWigHazardousB
→ const AisType
-
AIS_TYPE_WIG_HAZARDOUS_B
-
aisTypeWigHazardousC
→ const AisType
-
AIS_TYPE_WIG_HAZARDOUS_C
-
aisTypeWigHazardousD
→ const AisType
-
AIS_TYPE_WIG_HAZARDOUS_D
-
aisTypeWigReserved1
→ const AisType
-
AIS_TYPE_WIG_RESERVED_1
-
aisTypeWigReserved2
→ const AisType
-
AIS_TYPE_WIG_RESERVED_2
-
aisTypeWigReserved3
→ const AisType
-
AIS_TYPE_WIG_RESERVED_3
-
aisTypeWigReserved4
→ const AisType
-
AIS_TYPE_WIG_RESERVED_4
-
aisTypeWigReserved5
→ const AisType
-
AIS_TYPE_WIG_RESERVED_5
-
attitudeTargetTypemaskAttitudeIgnore
→ const AttitudeTargetTypemask
-
Ignore attitude
-
attitudeTargetTypemaskBodyPitchRateIgnore
→ const AttitudeTargetTypemask
-
Ignore body pitch rate
-
attitudeTargetTypemaskBodyRollRateIgnore
→ const AttitudeTargetTypemask
-
Ignore body roll rate
-
attitudeTargetTypemaskBodyYawRateIgnore
→ const AttitudeTargetTypemask
-
Ignore body yaw rate
-
attitudeTargetTypemaskThrottleIgnore
→ const AttitudeTargetTypemask
-
Ignore throttle
-
attitudeTargetTypemaskThrustBodySet
→ const AttitudeTargetTypemask
-
Use 3D body thrust setpoint instead of throttle
-
autotuneAxisDefault
→ const AutotuneAxis
-
Flight stack tunes axis according to its default settings.
-
autotuneAxisPitch
→ const AutotuneAxis
-
Autotune pitch axis.
-
autotuneAxisRoll
→ const AutotuneAxis
-
Autotune roll axis.
-
autotuneAxisYaw
→ const AutotuneAxis
-
Autotune yaw axis.
-
batteryFaultIncompatibleCellsConfiguration
→ const MavBatteryFault
-
Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).
-
cameraCapFlagsCanCaptureImageInVideoMode
→ const CameraCapFlags
-
Camera can capture images while in video mode
-
cameraCapFlagsCanCaptureVideoInImageMode
→ const CameraCapFlags
-
Camera can capture videos while in Photo/Image mode
-
cameraCapFlagsCaptureImage
→ const CameraCapFlags
-
Camera is able to capture images
-
cameraCapFlagsCaptureVideo
→ const CameraCapFlags
-
Camera is able to record video
-
cameraCapFlagsHasBasicFocus
→ const CameraCapFlags
-
Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)
-
cameraCapFlagsHasBasicZoom
→ const CameraCapFlags
-
Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)
-
cameraCapFlagsHasImageSurveyMode
→ const CameraCapFlags
-
Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)
-
cameraCapFlagsHasModes
→ const CameraCapFlags
-
Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)
-
cameraCapFlagsHasTrackingGeoStatus
→ const CameraCapFlags
-
Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS).
-
cameraCapFlagsHasTrackingPoint
→ const CameraCapFlags
-
Camera supports tracking of a point on the camera view.
-
cameraCapFlagsHasTrackingRectangle
→ const CameraCapFlags
-
Camera supports tracking of a selection rectangle on the camera view.
-
cameraCapFlagsHasVideoStream
→ const CameraCapFlags
-
Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)
-
cameraModeImage
→ const CameraMode
-
Camera is in image/photo capture mode.
-
cameraModeImageSurvey
→ const CameraMode
-
Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys.
-
cameraModeVideo
→ const CameraMode
-
Camera is in video capture mode.
-
cameraTrackingModeNone
→ const CameraTrackingMode
-
Not tracking
-
cameraTrackingModePoint
→ const CameraTrackingMode
-
Target is a point
-
cameraTrackingModeRectangle
→ const CameraTrackingMode
-
Target is a rectangle
-
cameraTrackingStatusFlagsActive
→ const CameraTrackingStatusFlags
-
Camera is tracking
-
cameraTrackingStatusFlagsError
→ const CameraTrackingStatusFlags
-
Camera tracking in error state
-
cameraTrackingStatusFlagsIdle
→ const CameraTrackingStatusFlags
-
Camera is not tracking
-
cameraTrackingTargetDataEmbedded
→ const CameraTrackingTargetData
-
Target data embedded in image data (proprietary)
-
cameraTrackingTargetDataInStatus
→ const CameraTrackingTargetData
-
Target data within status message (Point or Rectangle)
-
cameraTrackingTargetDataNone
→ const CameraTrackingTargetData
-
No target data
-
cameraTrackingTargetDataRendered
→ const CameraTrackingTargetData
-
Target data rendered in image
-
canFilterAdd
→ const CanFilterOp
-
CAN_FILTER_ADD
-
canFilterRemove
→ const CanFilterOp
-
CAN_FILTER_REMOVE
-
canFilterReplace
→ const CanFilterOp
-
CAN_FILTER_REPLACE
-
cellularConfigBlockedPukRequired
→ const CellularConfigResponse
-
PUK is required to unblock SIM card.
-
cellularConfigResponseAccepted
→ const CellularConfigResponse
-
Changes accepted.
-
cellularConfigResponseApnError
→ const CellularConfigResponse
-
Invalid APN.
-
cellularConfigResponsePinError
→ const CellularConfigResponse
-
Invalid PIN.
-
cellularConfigResponseRejected
→ const CellularConfigResponse
-
Changes rejected.
-
cellularNetworkFailedReasonNone
→ const CellularNetworkFailedReason
-
No error
-
cellularNetworkFailedReasonSimError
→ const CellularNetworkFailedReason
-
SIM is available, but not usable for connection
-
cellularNetworkFailedReasonSimMissing
→ const CellularNetworkFailedReason
-
SIM is required for the modem but missing
-
cellularNetworkFailedReasonUnknown
→ const CellularNetworkFailedReason
-
Error state is unknown
-
cellularNetworkRadioTypeCdma
→ const CellularNetworkRadioType
-
CELLULAR_NETWORK_RADIO_TYPE_CDMA
-
cellularNetworkRadioTypeGsm
→ const CellularNetworkRadioType
-
CELLULAR_NETWORK_RADIO_TYPE_GSM
-
cellularNetworkRadioTypeLte
→ const CellularNetworkRadioType
-
CELLULAR_NETWORK_RADIO_TYPE_LTE
-
cellularNetworkRadioTypeNone
→ const CellularNetworkRadioType
-
CELLULAR_NETWORK_RADIO_TYPE_NONE
-
cellularNetworkRadioTypeWcdma
→ const CellularNetworkRadioType
-
CELLULAR_NETWORK_RADIO_TYPE_WCDMA
-
cellularStatusFlagConnected
→ const CellularStatusFlag
-
One or more packet data bearers is active and connected
-
cellularStatusFlagConnecting
→ const CellularStatusFlag
-
Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered
-
cellularStatusFlagDisabled
→ const CellularStatusFlag
-
Modem is not enabled and is powered down
-
cellularStatusFlagDisabling
→ const CellularStatusFlag
-
Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state
-
cellularStatusFlagDisconnecting
→ const CellularStatusFlag
-
Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated
-
cellularStatusFlagEnabled
→ const CellularStatusFlag
-
Modem is enabled and powered on but not registered with a network provider and not available for data connections
-
cellularStatusFlagEnabling
→ const CellularStatusFlag
-
Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state
-
cellularStatusFlagFailed
→ const CellularStatusFlag
-
Modem is unusable
-
cellularStatusFlagInitializing
→ const CellularStatusFlag
-
Modem is being initialized
-
cellularStatusFlagLocked
→ const CellularStatusFlag
-
Modem is locked
-
cellularStatusFlagRegistered
→ const CellularStatusFlag
-
Modem is registered with a network provider, and data connections and messaging may be available for use
-
cellularStatusFlagSearching
→ const CellularStatusFlag
-
Modem is searching for a network provider to register
-
cellularStatusFlagUnknown
→ const CellularStatusFlag
-
State unknown or not reportable.
-
compMetadataTypeActuators
→ const CompMetadataType
-
Meta data for actuator configuration (motors, servos and vehicle geometry) and testing.
-
compMetadataTypeCommands
→ const CompMetadataType
-
Meta data that specifies which commands and command parameters the vehicle supports. (WIP)
-
compMetadataTypeEvents
→ const CompMetadataType
-
Meta data for the events interface.
-
compMetadataTypeGeneral
→ const CompMetadataType
-
General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI.
-
compMetadataTypeParameter
→ const CompMetadataType
-
Parameter meta data.
-
compMetadataTypePeripherals
→ const CompMetadataType
-
Meta data that specifies external non-MAVLink peripherals.
-
escConnectionTypeCan
→ const EscConnectionType
-
CAN-Bus ESC.
-
escConnectionTypeDshot
→ const EscConnectionType
-
DShot ESC.
-
escConnectionTypeI2c
→ const EscConnectionType
-
I2C ESC.
-
escConnectionTypeOneshot
→ const EscConnectionType
-
One Shot PPM ESC.
-
escConnectionTypePpm
→ const EscConnectionType
-
Traditional PPM ESC.
-
escConnectionTypeSerial
→ const EscConnectionType
-
Serial Bus connected ESC.
-
escFailureGeneric
→ const EscFailureFlags
-
Generic ESC failure.
-
escFailureInconsistentCmd
→ const EscFailureFlags
-
Inconsistent command failure i.e. out of bounds.
-
escFailureMotorStuck
→ const EscFailureFlags
-
Motor stuck failure.
-
escFailureNone
→ const EscFailureFlags
-
No ESC failure.
-
escFailureOverCurrent
→ const EscFailureFlags
-
Over current failure.
-
escFailureOverRpm
→ const EscFailureFlags
-
Over RPM failure.
-
escFailureOverTemperature
→ const EscFailureFlags
-
Over temperature failure.
-
escFailureOverVoltage
→ const EscFailureFlags
-
Over voltage failure.
-
estimatorAccelError
→ const EstimatorStatusFlags
-
True if the EKF has detected bad accelerometer data
-
estimatorAttitude
→ const EstimatorStatusFlags
-
True if the attitude estimate is good
-
estimatorConstPosMode
→ const EstimatorStatusFlags
-
True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
-
estimatorGpsGlitch
→ const EstimatorStatusFlags
-
True if the EKF has detected a GPS glitch
-
estimatorPosHorizAbs
→ const EstimatorStatusFlags
-
True if the horizontal position (absolute) estimate is good
-
estimatorPosHorizRel
→ const EstimatorStatusFlags
-
True if the horizontal position (relative) estimate is good
-
estimatorPosVertAbs
→ const EstimatorStatusFlags
-
True if the vertical position (absolute) estimate is good
-
estimatorPosVertAgl
→ const EstimatorStatusFlags
-
True if the vertical position (above ground) estimate is good
-
estimatorPredPosHorizAbs
→ const EstimatorStatusFlags
-
True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
-
estimatorPredPosHorizRel
→ const EstimatorStatusFlags
-
True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
-
estimatorVelocityHoriz
→ const EstimatorStatusFlags
-
True if the horizontal velocity estimate is good
-
estimatorVelocityVert
→ const EstimatorStatusFlags
-
True if the vertical velocity estimate is good
-
failureTypeDelayed
→ const FailureType
-
Data of unit is delayed in time.
-
failureTypeGarbage
→ const FailureType
-
Unit is reporting complete garbage.
-
failureTypeIntermittent
→ const FailureType
-
Unit is sometimes working, sometimes not.
-
failureTypeOff
→ const FailureType
-
Sets unit off, so completely non-responsive.
-
failureTypeOk
→ const FailureType
-
No failure injected, used to reset a previous failure.
-
failureTypeSlow
→ const FailureType
-
Unit is slow, so e.g. reporting at slower than expected rate.
-
failureTypeStuck
→ const FailureType
-
Unit is stuck e.g. keeps reporting the same value.
-
failureTypeWrong
→ const FailureType
-
Unit is consistently wrong.
-
failureUnitSensorAccel
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_ACCEL
-
failureUnitSensorAirspeed
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_AIRSPEED
-
failureUnitSensorBaro
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_BARO
-
failureUnitSensorDistanceSensor
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_DISTANCE_SENSOR
-
failureUnitSensorGps
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_GPS
-
failureUnitSensorGyro
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_GYRO
-
failureUnitSensorMag
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_MAG
-
failureUnitSensorOpticalFlow
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_OPTICAL_FLOW
-
failureUnitSensorVio
→ const FailureUnit
-
FAILURE_UNIT_SENSOR_VIO
-
failureUnitSystemAvoidance
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_AVOIDANCE
-
failureUnitSystemBattery
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_BATTERY
-
failureUnitSystemMavlinkSignal
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL
-
failureUnitSystemMotor
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_MOTOR
-
failureUnitSystemRcSignal
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_RC_SIGNAL
-
failureUnitSystemServo
→ const FailureUnit
-
FAILURE_UNIT_SYSTEM_SERVO
-
fenceActionGuided
→ const FenceAction
-
Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.
-
fenceActionGuidedThrPass
→ const FenceAction
-
Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.
-
fenceActionHold
→ const FenceAction
-
Hold at current location.
-
fenceActionLand
→ const FenceAction
-
Land at current location.
-
fenceActionNone
→ const FenceAction
-
Disable fenced mode. If used in a plan this would mean the next fence is disabled.
-
fenceActionReport
→ const FenceAction
-
Report fence breach, but don't take action
-
fenceActionRtl
→ const FenceAction
-
Return/RTL mode.
-
fenceActionTerminate
→ const FenceAction
-
Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions).
-
fenceBreachBoundary
→ const FenceBreach
-
Breached fence boundary
-
fenceBreachMaxalt
→ const FenceBreach
-
Breached maximum altitude
-
fenceBreachMinalt
→ const FenceBreach
-
Breached minimum altitude
-
fenceBreachNone
→ const FenceBreach
-
No last fence breach
-
fenceMitigateNone
→ const FenceMitigate
-
No actions being taken
-
fenceMitigateUnknown
→ const FenceMitigate
-
Unknown
-
fenceMitigateVelLimit
→ const FenceMitigate
-
Velocity limiting active to prevent breach
-
firmwareVersionTypeAlpha
→ const FirmwareVersionType
-
alpha release
-
firmwareVersionTypeBeta
→ const FirmwareVersionType
-
beta release
-
firmwareVersionTypeDev
→ const FirmwareVersionType
-
development release
-
firmwareVersionTypeOfficial
→ const FirmwareVersionType
-
official stable release
-
firmwareVersionTypeRc
→ const FirmwareVersionType
-
release candidate
-
focusTypeAuto
→ const SetFocusType
-
Focus automatically.
-
focusTypeAutoContinuous
→ const SetFocusType
-
Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C.
-
focusTypeAutoSingle
→ const SetFocusType
-
Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S.
-
focusTypeContinuous
→ const SetFocusType
-
Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing)
-
focusTypeMeters
→ const SetFocusType
-
Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera).
-
focusTypeRange
→ const SetFocusType
-
Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)
-
focusTypeStep
→ const SetFocusType
-
Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity).
-
gimbalDeviceCapFlagsHasNeutral
→ const GimbalDeviceCapFlags
-
Gimbal device supports a horizontal, forward looking position, stabilized.
-
gimbalDeviceCapFlagsHasPitchAxis
→ const GimbalDeviceCapFlags
-
Gimbal device supports rotating around pitch axis.
-
gimbalDeviceCapFlagsHasPitchFollow
→ const GimbalDeviceCapFlags
-
Gimbal device supports to follow a pitch angle relative to the vehicle.
-
gimbalDeviceCapFlagsHasPitchLock
→ const GimbalDeviceCapFlags
-
Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized).
-
gimbalDeviceCapFlagsHasRcInputs
→ const GimbalDeviceCapFlags
-
Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation.
-
gimbalDeviceCapFlagsHasRetract
→ const GimbalDeviceCapFlags
-
Gimbal device supports a retracted position.
-
gimbalDeviceCapFlagsHasRollAxis
→ const GimbalDeviceCapFlags
-
Gimbal device supports rotating around roll axis.
-
gimbalDeviceCapFlagsHasRollFollow
→ const GimbalDeviceCapFlags
-
Gimbal device supports to follow a roll angle relative to the vehicle.
-
gimbalDeviceCapFlagsHasRollLock
→ const GimbalDeviceCapFlags
-
Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized).
-
gimbalDeviceCapFlagsHasYawAxis
→ const GimbalDeviceCapFlags
-
Gimbal device supports rotating around yaw axis.
-
gimbalDeviceCapFlagsHasYawFollow
→ const GimbalDeviceCapFlags
-
Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).
-
gimbalDeviceCapFlagsHasYawLock
→ const GimbalDeviceCapFlags
-
Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).
-
gimbalDeviceCapFlagsSupportsInfiniteYaw
→ const GimbalDeviceCapFlags
-
Gimbal device supports yawing/panning infinitely (e.g. using slip disk).
-
gimbalDeviceCapFlagsSupportsYawInEarthFrame
→ const GimbalDeviceCapFlags
-
Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME.
-
gimbalDeviceErrorFlagsAtPitchLimit
→ const GimbalDeviceErrorFlags
-
Gimbal device is limited by hardware pitch limit.
-
gimbalDeviceErrorFlagsAtRollLimit
→ const GimbalDeviceErrorFlags
-
Gimbal device is limited by hardware roll limit.
-
gimbalDeviceErrorFlagsAtYawLimit
→ const GimbalDeviceErrorFlags
-
Gimbal device is limited by hardware yaw limit.
-
gimbalDeviceErrorFlagsCalibrationRunning
→ const GimbalDeviceErrorFlags
-
Gimbal device is currently calibrating.
-
gimbalDeviceErrorFlagsCommsError
→ const GimbalDeviceErrorFlags
-
There is an error with the gimbal's communication.
-
gimbalDeviceErrorFlagsEncoderError
→ const GimbalDeviceErrorFlags
-
There is an error with the gimbal encoders.
-
gimbalDeviceErrorFlagsMotorError
→ const GimbalDeviceErrorFlags
-
There is an error with the gimbal motors.
-
gimbalDeviceErrorFlagsNoManager
→ const GimbalDeviceErrorFlags
-
Gimbal device is not assigned to a gimbal manager.
-
gimbalDeviceErrorFlagsPowerError
→ const GimbalDeviceErrorFlags
-
There is an error with the gimbal power source.
-
gimbalDeviceErrorFlagsSoftwareError
→ const GimbalDeviceErrorFlags
-
There is an error with the gimbal's software.
-
gimbalDeviceFlagsAcceptsYawInEarthFrame
→ const GimbalDeviceFlags
-
Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored).
-
gimbalDeviceFlagsNeutral
→ const GimbalDeviceFlags
-
Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation.
-
gimbalDeviceFlagsPitchLock
→ const GimbalDeviceFlags
-
Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.
-
gimbalDeviceFlagsRcExclusive
→ const GimbalDeviceFlags
-
The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored.
-
gimbalDeviceFlagsRcMixed
→ const GimbalDeviceFlags
-
The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation.
-
gimbalDeviceFlagsRetract
→ const GimbalDeviceFlags
-
Set to retracted safe position (no stabilization), takes precedence over all other flags.
-
gimbalDeviceFlagsRollLock
→ const GimbalDeviceFlags
-
Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.
-
gimbalDeviceFlagsYawInEarthFrame
→ const GimbalDeviceFlags
-
Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).
-
gimbalDeviceFlagsYawInVehicleFrame
→ const GimbalDeviceFlags
-
Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward).
-
gimbalDeviceFlagsYawLock
→ const GimbalDeviceFlags
-
Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward).
-
gimbalManagerCapFlagsCanPointLocationGlobal
→ const GimbalManagerCapFlags
-
Gimbal manager supports to point to a global latitude, longitude, altitude position.
-
gimbalManagerCapFlagsCanPointLocationLocal
→ const GimbalManagerCapFlags
-
Gimbal manager supports to point to a local position.
-
gimbalManagerCapFlagsHasNeutral
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL.
-
gimbalManagerCapFlagsHasPitchAxis
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS.
-
gimbalManagerCapFlagsHasPitchFollow
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW.
-
gimbalManagerCapFlagsHasPitchLock
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK.
-
gimbalManagerCapFlagsHasRcInputs
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS.
-
gimbalManagerCapFlagsHasRetract
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT.
-
gimbalManagerCapFlagsHasRollAxis
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS.
-
gimbalManagerCapFlagsHasRollFollow
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW.
-
gimbalManagerCapFlagsHasRollLock
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK.
-
gimbalManagerCapFlagsHasYawAxis
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS.
-
gimbalManagerCapFlagsHasYawFollow
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW.
-
gimbalManagerCapFlagsHasYawLock
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK.
-
gimbalManagerCapFlagsSupportsInfiniteYaw
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW.
-
gimbalManagerCapFlagsSupportsYawInEarthFrame
→ const GimbalManagerCapFlags
-
Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME.
-
gimbalManagerFlagsAcceptsYawInEarthFrame
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME.
-
gimbalManagerFlagsNeutral
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_NEUTRAL.
-
gimbalManagerFlagsPitchLock
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK.
-
gimbalManagerFlagsRcExclusive
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE.
-
gimbalManagerFlagsRcMixed
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_RC_MIXED.
-
gimbalManagerFlagsRetract
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_RETRACT.
-
gimbalManagerFlagsRollLock
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK.
-
gimbalManagerFlagsYawInEarthFrame
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.
-
gimbalManagerFlagsYawInVehicleFrame
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME.
-
gimbalManagerFlagsYawLock
→ const GimbalManagerFlags
-
Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK.
-
gpsFixType2dFix
→ const GpsFixType
-
2D position
-
gpsFixType3dFix
→ const GpsFixType
-
3D position
-
gpsFixTypeDgps
→ const GpsFixType
-
DGPS/SBAS aided 3D position
-
gpsFixTypeNoFix
→ const GpsFixType
-
No position information, GPS is connected
-
gpsFixTypeNoGps
→ const GpsFixType
-
No GPS connected
-
gpsFixTypePpp
→ const GpsFixType
-
PPP, 3D position.
-
gpsFixTypeRtkFixed
→ const GpsFixType
-
RTK Fixed, 3D position
-
gpsFixTypeRtkFloat
→ const GpsFixType
-
RTK float, 3D position
-
gpsFixTypeStatic
→ const GpsFixType
-
Static fixed, typically used for base stations
-
gpsInputIgnoreFlagAlt
→ const GpsInputIgnoreFlags
-
ignore altitude field
-
gpsInputIgnoreFlagHdop
→ const GpsInputIgnoreFlags
-
ignore hdop field
-
gpsInputIgnoreFlagHorizontalAccuracy
→ const GpsInputIgnoreFlags
-
ignore horizontal accuracy field
-
gpsInputIgnoreFlagSpeedAccuracy
→ const GpsInputIgnoreFlags
-
ignore speed accuracy field
-
gpsInputIgnoreFlagVdop
→ const GpsInputIgnoreFlags
-
ignore vdop field
-
gpsInputIgnoreFlagVelHoriz
→ const GpsInputIgnoreFlags
-
ignore horizontal velocity field (vn and ve)
-
gpsInputIgnoreFlagVelVert
→ const GpsInputIgnoreFlags
-
ignore vertical velocity field (vd)
-
gpsInputIgnoreFlagVerticalAccuracy
→ const GpsInputIgnoreFlags
-
ignore vertical accuracy field
-
gripperActionGrab
→ const GripperActions
-
Gripper grab onto cargo.
-
gripperActionRelease
→ const GripperActions
-
Gripper release cargo.
-
highresImuUpdatedAbsPressure
→ const HighresImuUpdatedFlags
-
The value in the abs_pressure field has been updated
-
highresImuUpdatedAll
→ const HighresImuUpdatedFlags
-
All fields in HIGHRES_IMU have been updated.
-
highresImuUpdatedDiffPressure
→ const HighresImuUpdatedFlags
-
The value in the diff_pressure field has been updated
-
highresImuUpdatedNone
→ const HighresImuUpdatedFlags
-
None of the fields in HIGHRES_IMU have been updated
-
highresImuUpdatedPressureAlt
→ const HighresImuUpdatedFlags
-
The value in the pressure_alt field has been updated
-
highresImuUpdatedTemperature
→ const HighresImuUpdatedFlags
-
The value in the temperature field has been updated
-
highresImuUpdatedXacc
→ const HighresImuUpdatedFlags
-
The value in the xacc field has been updated
-
highresImuUpdatedXgyro
→ const HighresImuUpdatedFlags
-
The value in the xgyro field has been updated
-
highresImuUpdatedXmag
→ const HighresImuUpdatedFlags
-
The value in the xmag field has been updated
-
highresImuUpdatedYacc
→ const HighresImuUpdatedFlags
-
The value in the yacc field has been updated
-
highresImuUpdatedYgyro
→ const HighresImuUpdatedFlags
-
The value in the ygyro field has been updated
-
highresImuUpdatedYmag
→ const HighresImuUpdatedFlags
-
The value in the ymag field has been updated
-
highresImuUpdatedZacc
→ const HighresImuUpdatedFlags
-
The value in the zacc field has been updated since
-
highresImuUpdatedZgyro
→ const HighresImuUpdatedFlags
-
The value in the zgyro field has been updated
-
highresImuUpdatedZmag
→ const HighresImuUpdatedFlags
-
The value in the zmag field has been updated
-
hilSensorUpdatedAbsPressure
→ const HilSensorUpdatedFlags
-
The value in the abs_pressure field has been updated
-
hilSensorUpdatedDiffPressure
→ const HilSensorUpdatedFlags
-
The value in the diff_pressure field has been updated
-
hilSensorUpdatedNone
→ const HilSensorUpdatedFlags
-
None of the fields in HIL_SENSOR have been updated
-
hilSensorUpdatedPressureAlt
→ const HilSensorUpdatedFlags
-
The value in the pressure_alt field has been updated
-
hilSensorUpdatedReset
→ const HilSensorUpdatedFlags
-
Full reset of attitude/position/velocities/etc was performed in sim (Bit 31).
-
hilSensorUpdatedTemperature
→ const HilSensorUpdatedFlags
-
The value in the temperature field has been updated
-
hilSensorUpdatedXacc
→ const HilSensorUpdatedFlags
-
The value in the xacc field has been updated
-
hilSensorUpdatedXgyro
→ const HilSensorUpdatedFlags
-
The value in the xgyro field has been updated
-
hilSensorUpdatedXmag
→ const HilSensorUpdatedFlags
-
The value in the xmag field has been updated
-
hilSensorUpdatedYacc
→ const HilSensorUpdatedFlags
-
The value in the yacc field has been updated
-
hilSensorUpdatedYgyro
→ const HilSensorUpdatedFlags
-
The value in the ygyro field has been updated
-
hilSensorUpdatedYmag
→ const HilSensorUpdatedFlags
-
The value in the ymag field has been updated
-
hilSensorUpdatedZacc
→ const HilSensorUpdatedFlags
-
The value in the zacc field has been updated
-
hilSensorUpdatedZgyro
→ const HilSensorUpdatedFlags
-
The value in the zgyro field has been updated
-
hilSensorUpdatedZmag
→ const HilSensorUpdatedFlags
-
The value in the zmag field has been updated
-
hlFailureFlag3dAccel
→ const HlFailureFlag
-
Accelerometer sensor failure.
-
hlFailureFlag3dGyro
→ const HlFailureFlag
-
Gyroscope sensor failure.
-
hlFailureFlag3dMag
→ const HlFailureFlag
-
Magnetometer sensor failure.
-
hlFailureFlagAbsolutePressure
→ const HlFailureFlag
-
Absolute pressure sensor failure.
-
hlFailureFlagBattery
→ const HlFailureFlag
-
Battery failure/critical low battery.
-
hlFailureFlagDifferentialPressure
→ const HlFailureFlag
-
Differential pressure sensor failure.
-
hlFailureFlagEngine
→ const HlFailureFlag
-
Engine failure.
-
hlFailureFlagEstimator
→ const HlFailureFlag
-
Estimator failure, for example measurement rejection or large variances.
-
hlFailureFlagGeofence
→ const HlFailureFlag
-
Geofence violation.
-
hlFailureFlagGps
→ const HlFailureFlag
-
GPS failure.
-
hlFailureFlagMission
→ const HlFailureFlag
-
Mission failure.
-
hlFailureFlagOffboardLink
→ const HlFailureFlag
-
Offboard link failure.
-
hlFailureFlagRcReceiver
→ const HlFailureFlag
-
RC receiver failure/no RC connection.
-
hlFailureFlagTerrain
→ const HlFailureFlag
-
Terrain subsystem failure.
-
landingTargetTypeLightBeacon
→ const LandingTargetType
-
Landing target signaled by light beacon (ex: IR-LOCK)
-
landingTargetTypeRadioBeacon
→ const LandingTargetType
-
Landing target signaled by radio beacon (ex: ILS, NDB)
-
landingTargetTypeVisionFiducial
→ const LandingTargetType
-
Landing target represented by a fiducial marker (ex: ARTag)
-
landingTargetTypeVisionOther
→ const LandingTargetType
-
Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
-
magCalBadOrientation
→ const MagCalStatus
-
MAG_CAL_BAD_ORIENTATION
-
magCalBadRadius
→ const MagCalStatus
-
MAG_CAL_BAD_RADIUS
-
magCalFailed
→ const MagCalStatus
-
MAG_CAL_FAILED
-
magCalNotStarted
→ const MagCalStatus
-
MAG_CAL_NOT_STARTED
-
magCalRunningStepOne
→ const MagCalStatus
-
MAG_CAL_RUNNING_STEP_ONE
-
magCalRunningStepTwo
→ const MagCalStatus
-
MAG_CAL_RUNNING_STEP_TWO
-
magCalSuccess
→ const MagCalStatus
-
MAG_CAL_SUCCESS
-
magCalWaitingToStart
→ const MagCalStatus
-
MAG_CAL_WAITING_TO_START
-
mavArmAuthDeniedReasonAirspaceInUse
→ const MavArmAuthDeniedReason
-
Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied.
-
mavArmAuthDeniedReasonBadWeather
→ const MavArmAuthDeniedReason
-
Weather is not good to fly
-
mavArmAuthDeniedReasonGeneric
→ const MavArmAuthDeniedReason
-
Not a specific reason
-
mavArmAuthDeniedReasonInvalidWaypoint
→ const MavArmAuthDeniedReason
-
At least one waypoint have a invalid value
-
mavArmAuthDeniedReasonNone
→ const MavArmAuthDeniedReason
-
Authorizer will send the error as string to GCS
-
mavArmAuthDeniedReasonTimeout
→ const MavArmAuthDeniedReason
-
Timeout in the authorizer process(in case it depends on network)
-
mavAutopilotAerob
→ const MavAutopilot
-
Aerob -- http://aerob.ru
-
mavAutopilotAirrails
→ const MavAutopilot
-
AirRails - http://uaventure.com
-
mavAutopilotArdupilotmega
→ const MavAutopilot
-
ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org
-
mavAutopilotArmazila
→ const MavAutopilot
-
Armazila -- http://armazila.com
-
mavAutopilotAsluav
→ const MavAutopilot
-
ASLUAV autopilot -- http://www.asl.ethz.ch
-
mavAutopilotAutoquad
→ const MavAutopilot
-
AutoQuad -- http://autoquad.org
-
mavAutopilotFp
→ const MavAutopilot
-
FlexiPilot
-
mavAutopilotGeneric
→ const MavAutopilot
-
Generic autopilot, full support for everything
-
mavAutopilotGenericMissionFull
→ const MavAutopilot
-
Generic autopilot supporting the full mission command set
-
mavAutopilotGenericWaypointsAndSimpleNavigationOnly
→ const MavAutopilot
-
Generic autopilot supporting waypoints and other simple navigation commands
-
mavAutopilotGenericWaypointsOnly
→ const MavAutopilot
-
Generic autopilot only supporting simple waypoints
-
mavAutopilotInvalid
→ const MavAutopilot
-
No valid autopilot, e.g. a GCS or other MAVLink component
-
mavAutopilotOpenpilot
→ const MavAutopilot
-
OpenPilot, http://openpilot.org
-
mavAutopilotPpz
→ const MavAutopilot
-
PPZ UAV - http://nongnu.org/paparazzi
-
mavAutopilotPx4
→ const MavAutopilot
-
PX4 Autopilot - http://px4.io/
-
mavAutopilotReflex
→ const MavAutopilot
-
Fusion Reflex - https://fusion.engineering
-
mavAutopilotReserved
→ const MavAutopilot
-
Reserved for future use.
-
mavAutopilotSlugs
→ const MavAutopilot
-
SLUGS autopilot, http://slugsuav.soe.ucsc.edu
-
mavAutopilotSmaccmpilot
→ const MavAutopilot
-
SMACCMPilot - http://smaccmpilot.org
-
mavAutopilotSmartap
→ const MavAutopilot
-
SmartAP Autopilot - http://sky-drones.com
-
mavAutopilotUdb
→ const MavAutopilot
-
UAV Dev Board
-
mavBatteryChargeStateCharging
→ const MavBatteryChargeState
-
Battery is charging.
-
mavBatteryChargeStateCritical
→ const MavBatteryChargeState
-
Battery state is critical, return or abort immediately.
-
mavBatteryChargeStateEmergency
→ const MavBatteryChargeState
-
Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage.
-
mavBatteryChargeStateFailed
→ const MavBatteryChargeState
-
Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT.
-
mavBatteryChargeStateLow
→ const MavBatteryChargeState
-
Battery state is low, warn and monitor close.
-
mavBatteryChargeStateOk
→ const MavBatteryChargeState
-
Battery is not in low state. Normal operation.
-
mavBatteryChargeStateUndefined
→ const MavBatteryChargeState
-
Low battery state is not provided
-
mavBatteryChargeStateUnhealthy
→ const MavBatteryChargeState
-
Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT.
-
mavBatteryFaultCellFail
→ const MavBatteryFault
-
One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used).
-
mavBatteryFaultDeepDischarge
→ const MavBatteryFault
-
Battery has deep discharged.
-
mavBatteryFaultIncompatibleFirmware
→ const MavBatteryFault
-
Battery firmware is not compatible with current autopilot firmware.
-
mavBatteryFaultIncompatibleVoltage
→ const MavBatteryFault
-
Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
-
mavBatteryFaultOverCurrent
→ const MavBatteryFault
-
Over-current fault.
-
mavBatteryFaultOverTemperature
→ const MavBatteryFault
-
Over-temperature fault.
-
mavBatteryFaultSpikes
→ const MavBatteryFault
-
Voltage spikes.
-
mavBatteryFaultUnderTemperature
→ const MavBatteryFault
-
Under-temperature fault.
-
mavBatteryFunctionAll
→ const MavBatteryFunction
-
Battery supports all flight systems
-
mavBatteryFunctionAvionics
→ const MavBatteryFunction
-
Avionics battery
-
mavBatteryFunctionPayload
→ const MavBatteryFunction
-
Payload battery
-
mavBatteryFunctionPropulsion
→ const MavBatteryFunction
-
Battery for the propulsion system
-
mavBatteryFunctionUnknown
→ const MavBatteryFunction
-
Battery function is unknown
-
mavBatteryModeAutoDischarging
→ const MavBatteryMode
-
Battery is auto discharging (towards storage level).
-
mavBatteryModeHotSwap
→ const MavBatteryMode
-
Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits).
-
mavBatteryModeUnknown
→ const MavBatteryMode
-
Battery mode not supported/unknown battery mode/normal operation.
-
mavBatteryTypeLife
→ const MavBatteryType
-
Lithium-iron-phosphate battery
-
mavBatteryTypeLion
→ const MavBatteryType
-
Lithium-ION battery
-
mavBatteryTypeLipo
→ const MavBatteryType
-
Lithium polymer battery
-
mavBatteryTypeNimh
→ const MavBatteryType
-
Nickel metal hydride battery
-
mavBatteryTypeUnknown
→ const MavBatteryType
-
Not specified.
-
mavCmdActuatorTest
→ const MavCmd
-
Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots typically refuse this command while armed.
-
mavCmdAirframeConfiguration
→ const MavCmd
-
MAV_CMD_AIRFRAME_CONFIGURATION
-
mavCmdArmAuthorizationRequest
→ const MavCmd
-
Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request.
If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds.
If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
-
mavCmdCameraStopTracking
→ const MavCmd
-
Stops ongoing tracking.
-
mavCmdCameraTrackPoint
→ const MavCmd
-
If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking.
-
mavCmdCameraTrackRectangle
→ const MavCmd
-
If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking.
-
mavCmdCanForward
→ const MavCmd
-
Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages
-
mavCmdComponentArmDisarm
→ const MavCmd
-
Arms / Disarms a component
-
mavCmdConditionChangeAlt
→ const MavCmd
-
Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached.
-
mavCmdConditionDelay
→ const MavCmd
-
Delay mission state machine.
-
mavCmdConditionDistance
→ const MavCmd
-
Delay mission state machine until within desired distance of next NAV point.
-
mavCmdConditionGate
→ const MavCmd
-
WIP.
Delay mission state machine until gate has been reached.
-
mavCmdConditionLast
→ const MavCmd
-
NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration
-
mavCmdConditionYaw
→ const MavCmd
-
Reach a certain target angle.
-
mavCmdConfigureActuator
→ const MavCmd
-
Actuator configuration command.
-
mavCmdControlHighLatency
→ const MavCmd
-
Request to start/stop transmitting over the high latency telemetry
-
mavCmdDoAdsbOutIdent
→ const MavCmd
-
Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec.
-
mavCmdDoAutotuneEnable
→ const MavCmd
-
Enable/disable autotune.
-
mavCmdDoChangeAltitude
→ const MavCmd
-
Change altitude set point.
-
mavCmdDoChangeSpeed
→ const MavCmd
-
Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change
-
mavCmdDoControlVideo
→ const MavCmd
-
Control onboard camera system.
-
mavCmdDoDigicamConfigure
→ const MavCmd
-
Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).
-
mavCmdDoDigicamControl
→ const MavCmd
-
Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).
-
mavCmdDoEngineControl
→ const MavCmd
-
Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines
-
mavCmdDoFenceEnable
→ const MavCmd
-
Mission command to enable the geofence
-
mavCmdDoFlighttermination
→ const MavCmd
-
Terminate flight immediately.
Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground.
The vehicle will ignore RC or other input until it has been power-cycled.
Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing).
On multicopters without a parachute it may trigger a crash landing.
Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION.
Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.
-
mavCmdDoFollow
→ const MavCmd
-
Begin following a target
-
mavCmdDoFollowReposition
→ const MavCmd
-
Reposition the MAV after a follow target command has been sent
-
mavCmdDoGimbalManagerConfigure
→ const MavCmd
-
Gimbal configuration to set which sysid/compid is in primary and secondary control.
-
mavCmdDoGimbalManagerPitchyaw
→ const MavCmd
-
Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate.
-
mavCmdDoGoAround
→ const MavCmd
-
Mission command to safely abort an autonomous landing.
-
mavCmdDoGripper
→ const MavCmd
-
Mission command to operate a gripper.
-
mavCmdDoGuidedLimits
→ const MavCmd
-
Set limits for external control
-
mavCmdDoGuidedMaster
→ const MavCmd
-
set id of master controller
-
mavCmdDoInvertedFlight
→ const MavCmd
-
Change to/from inverted flight.
-
mavCmdDoJump
→ const MavCmd
-
Jump to the desired command in the mission list. Repeat this action only the specified number of times
-
mavCmdDoJumpTag
→ const MavCmd
-
Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number.
-
mavCmdDoLandStart
→ const MavCmd
-
Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts.
It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used.
The Latitude/Longitude/Altitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence.
-
mavCmdDoLast
→ const MavCmd
-
NOP - This command is only used to mark the upper limit of the DO commands in the enumeration
-
mavCmdDoMotorTest
→ const MavCmd
-
Command to perform motor test.
-
mavCmdDoMountConfigure
→ const MavCmd
-
Mission command to configure a camera or antenna mount
-
mavCmdDoMountControl
→ const MavCmd
-
Mission command to control a camera or antenna mount
-
mavCmdDoMountControlQuat
→ const MavCmd
-
Mission command to control a camera or antenna mount, using a quaternion as reference.
-
mavCmdDoOrbit
→ const MavCmd
-
WIP.
Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults.
-
mavCmdDoParachute
→ const MavCmd
-
Mission item/command to release a parachute or enable/disable auto release.
-
mavCmdDoPauseContinue
→ const MavCmd
-
If in a GPS controlled position mode, hold the current position or continue.
-
mavCmdDoRallyLand
→ const MavCmd
-
Mission command to perform a landing from a rally point.
-
mavCmdDoRepeatRelay
→ const MavCmd
-
Cycle a relay on and off for a desired number of cycles with a desired period.
-
mavCmdDoRepeatServo
→ const MavCmd
-
Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.
-
mavCmdDoReposition
→ const MavCmd
-
Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead).
-
mavCmdDoSetActuator
→ const MavCmd
-
Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter).
-
mavCmdDoSetCamTriggDist
→ const MavCmd
-
Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera.
-
mavCmdDoSetCamTriggInterval
→ const MavCmd
-
Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera.
-
mavCmdDoSetHome
→ const MavCmd
-
Sets the home position to either to the current position or a specified position.
The home position is the default position that the system will return to and land on.
The position is set automatically by the system during the takeoff (and may also be set using this command).
Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
-
mavCmdDoSetMissionCurrent
→ const MavCmd
-
Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed).
If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items.
Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2).
-
mavCmdDoSetMode
→ const MavCmd
-
Set system mode.
-
mavCmdDoSetParameter
→ const MavCmd
-
Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.
-
mavCmdDoSetRelay
→ const MavCmd
-
Set a relay to a condition.
-
mavCmdDoSetReverse
→ const MavCmd
-
Set moving direction to forward or reverse.
-
mavCmdDoSetRoi
→ const MavCmd
-
Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras.
-
mavCmdDoSetRoiLocation
→ const MavCmd
-
Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message.
-
mavCmdDoSetRoiNone
→ const MavCmd
-
Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position.
-
mavCmdDoSetRoiSysid
→ const MavCmd
-
Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.
-
mavCmdDoSetRoiWpnextOffset
→ const MavCmd
-
Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.
-
mavCmdDoSetSafetySwitchState
→ const MavCmd
-
Change state of safety switch.
-
mavCmdDoSetServo
→ const MavCmd
-
Set a servo to a desired PWM value.
-
mavCmdDoTriggerControl
→ const MavCmd
-
Enable or disable on-board camera triggering system.
-
mavCmdDoVtolTransition
→ const MavCmd
-
Request VTOL transition
-
mavCmdDoWinch
→ const MavCmd
-
Command to operate winch.
-
mavCmdExternalPositionEstimate
→ const MavCmd
-
Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.
-
mavCmdFixedMagCalYaw
→ const MavCmd
-
Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.
-
mavCmdGetHomePosition
→ const MavCmd
-
Request the home position from the vehicle.
The vehicle will ACK the command and then emit the HOME_POSITION message.
-
mavCmdGetMessageInterval
→ const MavCmd
-
Request the interval between messages for a particular MAVLink message ID.
The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message.
-
mavCmdIlluminatorOnOff
→ const MavCmd
-
WIP.
Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light).
-
mavCmdImageStartCapture
→ const MavCmd
-
Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture.
-
mavCmdImageStopCapture
→ const MavCmd
-
Stop image capture sequence.
-
mavCmdInjectFailure
→ const MavCmd
-
Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting.
-
mavCmdJumpTag
→ const MavCmd
-
Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG.
-
mavCmdLoggingStart
→ const MavCmd
-
Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)
-
mavCmdLoggingStop
→ const MavCmd
-
Request to stop streaming log data over MAVLink
-
mavCmdMissionStart
→ const MavCmd
-
start running a mission
-
mavCmdNavContinueAndChangeAlt
→ const MavCmd
-
Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.
-
mavCmdNavDelay
→ const MavCmd
-
Delay the next navigation command a number of seconds or until a specified time
-
mavCmdNavFenceCircleExclusion
→ const MavCmd
-
Circular fence area. The vehicle must stay outside this area.
-
mavCmdNavFenceCircleInclusion
→ const MavCmd
-
Circular fence area. The vehicle must stay inside this area.
-
mavCmdNavFencePolygonVertexExclusion
→ const MavCmd
-
Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.
-
mavCmdNavFencePolygonVertexInclusion
→ const MavCmd
-
Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required.
-
mavCmdNavFenceReturnPoint
→ const MavCmd
-
Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead.
-
mavCmdNavFollow
→ const MavCmd
-
Vehicle following, i.e. this waypoint represents the position of a moving vehicle
-
mavCmdNavGuidedEnable
→ const MavCmd
-
hand control over to an external controller
-
mavCmdNavLand
→ const MavCmd
-
Land at location.
-
mavCmdNavLandLocal
→ const MavCmd
-
Land at local position (local frame only)
-
mavCmdNavLast
→ const MavCmd
-
NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration
-
mavCmdNavLoiterTime
→ const MavCmd
-
Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint.
-
mavCmdNavLoiterToAlt
→ const MavCmd
-
Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint.
-
mavCmdNavLoiterTurns
→ const MavCmd
-
Loiter around this waypoint for X turns
-
mavCmdNavLoiterUnlim
→ const MavCmd
-
Loiter around this waypoint an unlimited amount of time
-
mavCmdNavPathplanning
→ const MavCmd
-
Control autonomous path planning on the MAV.
-
mavCmdNavPayloadPlace
→ const MavCmd
-
Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload.
-
mavCmdNavRallyPoint
→ const MavCmd
-
Rally point. You can have multiple rally points defined.
-
mavCmdNavReturnToLaunch
→ const MavCmd
-
Return to launch location
-
mavCmdNavRoi
→ const MavCmd
-
Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras.
-
mavCmdNavSetYawSpeed
→ const MavCmd
-
Sets a desired vehicle turn angle and speed change.
-
mavCmdNavSplineWaypoint
→ const MavCmd
-
Navigate to waypoint using a spline path.
-
mavCmdNavTakeoff
→ const MavCmd
-
Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.
-
mavCmdNavTakeoffLocal
→ const MavCmd
-
Takeoff from local position (local frame only)
-
mavCmdNavVtolLand
→ const MavCmd
-
Land using VTOL mode
-
mavCmdNavVtolTakeoff
→ const MavCmd
-
Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.).
-
mavCmdNavWaypoint
→ const MavCmd
-
Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION).
-
mavCmdObliqueSurvey
→ const MavCmd
-
Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera.
-
mavCmdOverrideGoto
→ const MavCmd
-
Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position.
-
mavCmdPanoramaCreate
→ const MavCmd
-
Create a panorama at the current position
-
mavCmdPayloadControlDeploy
→ const MavCmd
-
Control the payload deployment.
-
mavCmdPayloadPrepareDeploy
→ const MavCmd
-
Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.
-
mavCmdPreflightCalibration
→ const MavCmd
-
Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero.
-
mavCmdPreflightRebootShutdown
→ const MavCmd
-
Request the reboot or shutdown of system components.
-
mavCmdPreflightSetSensorOffsets
→ const MavCmd
-
Set sensor offsets. This command will be only accepted if in pre-flight mode.
-
mavCmdPreflightStorage
→ const MavCmd
-
Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.
-
mavCmdPreflightUavcan
→ const MavCmd
-
Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named).
-
mavCmdRequestAutopilotCapabilities
→ const MavCmd
-
Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message
-
mavCmdRequestCameraCaptureStatus
→ const MavCmd
-
Request camera capture status (CAMERA_CAPTURE_STATUS)
-
mavCmdRequestCameraImageCapture
→ const MavCmd
-
Re-request a CAMERA_IMAGE_CAPTURED message.
-
mavCmdRequestCameraInformation
→ const MavCmd
-
Request camera information (CAMERA_INFORMATION).
-
mavCmdRequestCameraSettings
→ const MavCmd
-
Request camera settings (CAMERA_SETTINGS).
-
mavCmdRequestFlightInformation
→ const MavCmd
-
Request flight information (FLIGHT_INFORMATION)
-
mavCmdRequestMessage
→ const MavCmd
-
Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL).
-
mavCmdRequestProtocolVersion
→ const MavCmd
-
Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message
-
mavCmdRequestStorageInformation
→ const MavCmd
-
Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage.
-
mavCmdRequestVideoStreamInformation
→ const MavCmd
-
Request video stream information (VIDEO_STREAM_INFORMATION)
-
mavCmdRequestVideoStreamStatus
→ const MavCmd
-
Request video stream status (VIDEO_STREAM_STATUS)
-
mavCmdResetCameraSettings
→ const MavCmd
-
Reset all camera settings to Factory Default
-
mavCmdRunPrearmChecks
→ const MavCmd
-
Instructs a target system to run pre-arm checks.
This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed.
This command should return MAV_RESULT_ACCEPTED if it will run the checks.
The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific).
The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed.
-
mavCmdSetCameraFocus
→ const MavCmd
-
Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success).
-
mavCmdSetCameraMode
→ const MavCmd
-
Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming.
-
mavCmdSetCameraZoom
→ const MavCmd
-
Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success).
-
mavCmdSetGuidedSubmodeCircle
→ const MavCmd
-
This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.
-
mavCmdSetGuidedSubmodeStandard
→ const MavCmd
-
This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.
-
mavCmdSetMessageInterval
→ const MavCmd
-
Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM.
-
mavCmdSetStorageUsage
→ const MavCmd
-
Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos).
There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage.
If no flag is set the system should use its default storage.
A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED.
A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED.
-
mavCmdSpatialUser1
→ const MavCmd
-
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
-
mavCmdSpatialUser2
→ const MavCmd
-
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
-
mavCmdSpatialUser3
→ const MavCmd
-
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
-
mavCmdSpatialUser4
→ const MavCmd
-
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
-
mavCmdSpatialUser5
→ const MavCmd
-
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
-
mavCmdStartRxPair
→ const MavCmd
-
Starts receiver pairing.
-
mavCmdStorageFormat
→ const MavCmd
-
Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage.
-
mavCmdUavcanGetNodeInfo
→ const MavCmd
-
Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages.
-
mavCmdUser1
→ const MavCmd
-
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
-
mavCmdUser2
→ const MavCmd
-
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
-
mavCmdUser3
→ const MavCmd
-
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
-
mavCmdUser4
→ const MavCmd
-
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
-
mavCmdUser5
→ const MavCmd
-
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
-
mavCmdVideoStartCapture
→ const MavCmd
-
Starts video capture (recording).
-
mavCmdVideoStartStreaming
→ const MavCmd
-
Start video streaming
-
mavCmdVideoStopCapture
→ const MavCmd
-
Stop the current video capture (recording).
-
mavCmdVideoStopStreaming
→ const MavCmd
-
Stop the given video stream
-
mavCmdWaypointUser1
→ const MavCmd
-
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
-
mavCmdWaypointUser2
→ const MavCmd
-
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
-
mavCmdWaypointUser3
→ const MavCmd
-
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
-
mavCmdWaypointUser4
→ const MavCmd
-
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
-
mavCmdWaypointUser5
→ const MavCmd
-
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
-
mavCollisionActionAscendOrDescend
→ const MavCollisionAction
-
Ascend or Descend to avoid threat
-
mavCollisionActionHover
→ const MavCollisionAction
-
Aircraft to stop in place
-
mavCollisionActionMoveHorizontally
→ const MavCollisionAction
-
Move horizontally to avoid threat
-
mavCollisionActionMovePerpendicular
→ const MavCollisionAction
-
Aircraft to move perpendicular to the collision's velocity vector
-
mavCollisionActionNone
→ const MavCollisionAction
-
Ignore any potential collisions
-
mavCollisionActionReport
→ const MavCollisionAction
-
Report potential collision
-
mavCollisionActionRtl
→ const MavCollisionAction
-
Aircraft to fly directly back to its launch point
-
mavCollisionSrcAdsb
→ const MavCollisionSrc
-
ID field references ADSB_VEHICLE packets
-
mavCollisionSrcMavlinkGpsGlobalInt
→ const MavCollisionSrc
-
ID field references MAVLink SRC ID
-
mavCollisionThreatLevelHigh
→ const MavCollisionThreatLevel
-
Craft is panicking, and may take actions to avoid threat
-
mavCollisionThreatLevelLow
→ const MavCollisionThreatLevel
-
Craft is mildly concerned about this threat
-
mavCollisionThreatLevelNone
→ const MavCollisionThreatLevel
-
Not a threat
-
mavCompIdAdsb
→ const MavComponent
-
Automatic Dependent Surveillance-Broadcast (ADS-B) component.
-
mavCompIdAll
→ const MavComponent
-
Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid source component id for a message.
-
mavCompIdAutopilot1
→ const MavComponent
-
System flight controller component ("autopilot"). Only one autopilot is expected in a particular system.
-
mavCompIdBattery
→ const MavComponent
-
Battery #1.
-
mavCompIdBattery2
→ const MavComponent
-
Battery #2.
-
mavCompIdCamera
→ const MavComponent
-
Camera #1.
-
mavCompIdCamera2
→ const MavComponent
-
Camera #2.
-
mavCompIdCamera3
→ const MavComponent
-
Camera #3.
-
mavCompIdCamera4
→ const MavComponent
-
Camera #4.
-
mavCompIdCamera5
→ const MavComponent
-
Camera #5.
-
mavCompIdCamera6
→ const MavComponent
-
Camera #6.
-
mavCompIdFlarm
→ const MavComponent
-
FLARM collision alert component.
-
mavCompIdGimbal
→ const MavComponent
-
Gimbal #1.
-
mavCompIdGimbal2
→ const MavComponent
-
Gimbal #2.
-
mavCompIdGimbal3
→ const MavComponent
-
Gimbal #3.
-
mavCompIdGimbal4
→ const MavComponent
-
Gimbal #4
-
mavCompIdGimbal5
→ const MavComponent
-
Gimbal #5.
-
mavCompIdGimbal6
→ const MavComponent
-
Gimbal #6.
-
mavCompIdGps
→ const MavComponent
-
GPS #1.
-
mavCompIdGps2
→ const MavComponent
-
GPS #2.
-
mavCompIdImu
→ const MavComponent
-
Inertial Measurement Unit (IMU) #1.
-
mavCompIdImu2
→ const MavComponent
-
Inertial Measurement Unit (IMU) #2.
-
mavCompIdImu3
→ const MavComponent
-
Inertial Measurement Unit (IMU) #3.
-
mavCompIdLog
→ const MavComponent
-
Logging component.
-
mavCompIdMavcan
→ const MavComponent
-
CAN over MAVLink client.
-
mavCompIdMissionplanner
→ const MavComponent
-
Component that can generate/supply a mission flight plan (e.g. GCS or developer API).
-
mavCompIdObstacleAvoidance
→ const MavComponent
-
Component that plans a collision free path between two points.
-
mavCompIdOdidTxrx1
→ const MavComponent
-
Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
-
mavCompIdOdidTxrx2
→ const MavComponent
-
Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
-
mavCompIdOdidTxrx3
→ const MavComponent
-
Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
-
mavCompIdOnboardComputer
→ const MavComponent
-
Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
-
mavCompIdOnboardComputer2
→ const MavComponent
-
Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
-
mavCompIdOnboardComputer3
→ const MavComponent
-
Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
-
mavCompIdOnboardComputer4
→ const MavComponent
-
Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
-
mavCompIdOsd
→ const MavComponent
-
On Screen Display (OSD) devices for video links.
-
mavCompIdPairingManager
→ const MavComponent
-
Component that manages pairing of vehicle and GCS.
-
mavCompIdParachute
→ const MavComponent
-
Parachute component.
-
mavCompIdPathplanner
→ const MavComponent
-
Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
-
mavCompIdPeripheral
→ const MavComponent
-
Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice.
-
mavCompIdQx1Gimbal
→ const MavComponent
-
Gimbal ID for QX1.
-
mavCompIdServo1
→ const MavComponent
-
Servo #1.
-
mavCompIdServo10
→ const MavComponent
-
Servo #10.
-
mavCompIdServo11
→ const MavComponent
-
Servo #11.
-
mavCompIdServo12
→ const MavComponent
-
Servo #12.
-
mavCompIdServo13
→ const MavComponent
-
Servo #13.
-
mavCompIdServo14
→ const MavComponent
-
Servo #14.
-
mavCompIdServo2
→ const MavComponent
-
Servo #2.
-
mavCompIdServo3
→ const MavComponent
-
Servo #3.
-
mavCompIdServo4
→ const MavComponent
-
Servo #4.
-
mavCompIdServo5
→ const MavComponent
-
Servo #5.
-
mavCompIdServo6
→ const MavComponent
-
Servo #6.
-
mavCompIdServo7
→ const MavComponent
-
Servo #7.
-
mavCompIdServo8
→ const MavComponent
-
Servo #8.
-
mavCompIdServo9
→ const MavComponent
-
Servo #9.
-
mavCompIdSystemControl
→ const MavComponent
-
Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.).
-
mavCompIdTelemetryRadio
→ const MavComponent
-
Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
-
mavCompIdTunnelNode
→ const MavComponent
-
Component handling TUNNEL messages (e.g. vendor specific GUI of a component).
-
mavCompIdUartBridge
→ const MavComponent
-
Component to bridge to UART (i.e. from UDP).
-
mavCompIdUdpBridge
→ const MavComponent
-
Component to bridge MAVLink to UDP (i.e. from a UART).
-
mavCompIdUser1
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser10
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser11
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser12
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser13
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser14
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser15
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser16
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser17
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser18
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser19
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser2
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser20
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser21
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser22
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser23
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser24
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser25
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser26
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser27
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser28
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser29
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser3
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser30
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser31
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser32
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser33
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser34
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser35
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser36
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser37
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser38
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser39
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser4
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser40
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser41
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser42
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser43
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser45
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser46
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser47
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser48
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser49
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser5
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser50
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser51
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser52
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser53
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser54
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser55
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser56
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser57
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser58
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser59
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser6
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser60
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser61
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser62
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser63
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser64
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser65
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser66
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser67
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser68
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser69
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser7
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser70
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser71
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser72
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser73
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser74
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser75
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser8
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdUser9
→ const MavComponent
-
Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
-
mavCompIdVisualInertialOdometry
→ const MavComponent
-
Component that provides position estimates using VIO techniques.
-
mavCompIdWinch
→ const MavComponent
-
Winch component.
-
mavDataStreamAll
→ const MavDataStream
-
Enable all data streams
-
mavDataStreamExtendedStatus
→ const MavDataStream
-
Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
-
Dependent on the autopilot
-
Dependent on the autopilot
-
Dependent on the autopilot
-
mavDataStreamPosition
→ const MavDataStream
-
Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages.
-
mavDataStreamRawController
→ const MavDataStream
-
Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
-
mavDataStreamRawSensors
→ const MavDataStream
-
Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
-
mavDataStreamRcChannels
→ const MavDataStream
-
Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
-
mavDistanceSensorInfrared
→ const MavDistanceSensor
-
Infrared rangefinder, e.g. Sharp units
-
mavDistanceSensorLaser
→ const MavDistanceSensor
-
Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
-
mavDistanceSensorRadar
→ const MavDistanceSensor
-
Radar type, e.g. uLanding units
-
mavDistanceSensorUltrasound
→ const MavDistanceSensor
-
Ultrasound rangefinder, e.g. MaxBotix units
-
mavDistanceSensorUnknown
→ const MavDistanceSensor
-
Broken or unknown type, e.g. analog units
-
mavDoRepositionFlagsChangeMode
→ const MavDoRepositionFlags
-
The aircraft should immediately transition into guided. This should not be set for follow me applications
-
mavEstimatorTypeAutopilot
→ const MavEstimatorType
-
Estimator on autopilot.
-
mavEstimatorTypeGps
→ const MavEstimatorType
-
Plain GPS estimate.
-
mavEstimatorTypeGpsIns
→ const MavEstimatorType
-
Estimator integrating GPS and inertial sensing.
-
mavEstimatorTypeLidar
→ const MavEstimatorType
-
Estimator based on lidar sensor input.
-
mavEstimatorTypeMocap
→ const MavEstimatorType
-
Estimate from external motion capturing system.
-
mavEstimatorTypeNaive
→ const MavEstimatorType
-
This is a naive estimator without any real covariance feedback.
-
mavEstimatorTypeUnknown
→ const MavEstimatorType
-
Unknown type of the estimator.
-
mavEstimatorTypeVio
→ const MavEstimatorType
-
Visual-inertial estimate.
-
mavEstimatorTypeVision
→ const MavEstimatorType
-
Computer vision based estimate. Might be up to scale.
-
mavEventCurrentSequenceFlagsReset
→ const MavEventCurrentSequenceFlags
-
A sequence reset has happened (e.g. vehicle reboot).
-
mavEventErrorReasonUnavailable
→ const MavEventErrorReason
-
The requested event is not available (anymore).
-
mavFrameBodyFrd
→ const MavFrame
-
FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
-
mavFrameBodyNed
→ const MavFrame
-
Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.
-
mavFrameBodyOffsetNed
→ const MavFrame
-
This is the same as MAV_FRAME_BODY_FRD.
-
mavFrameGlobal
→ const MavFrame
-
Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
-
mavFrameGlobalInt
→ const MavFrame
-
Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude over mean sea level (MSL).
-
mavFrameGlobalRelativeAlt
→ const MavFrame
-
Global (WGS84) coordinate frame + altitude relative to the home position.
First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position.
-
mavFrameGlobalRelativeAltInt
→ const MavFrame
-
Global (WGS84) coordinate frame (scaled) + altitude relative to the home position.
First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude with 0 being at the altitude of the home position.
-
mavFrameGlobalTerrainAlt
→ const MavFrame
-
Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
-
mavFrameGlobalTerrainAltInt
→ const MavFrame
-
Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
-
mavFrameLocalEnu
→ const MavFrame
-
ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.
-
mavFrameLocalFlu
→ const MavFrame
-
FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
-
mavFrameLocalFrd
→ const MavFrame
-
FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
-
mavFrameLocalNed
→ const MavFrame
-
NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
-
mavFrameLocalOffsetNed
→ const MavFrame
-
NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.
-
mavFrameMission
→ const MavFrame
-
NOT a coordinate frame, indicates a mission command.
-
mavFrameReserved13
→ const MavFrame
-
MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
-
mavFrameReserved14
→ const MavFrame
-
MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).
-
mavFrameReserved15
→ const MavFrame
-
MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).
-
mavFrameReserved16
→ const MavFrame
-
MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).
-
mavFrameReserved17
→ const MavFrame
-
MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up).
-
mavFrameReserved18
→ const MavFrame
-
MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down).
-
mavFrameReserved19
→ const MavFrame
-
MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up).
-
mavFtpErrEof
→ const MavFtpErr
-
EOF: Offset past end of file for ListDirectory and ReadFile commands
-
mavFtpErrFail
→ const MavFtpErr
-
Fail: Unknown failure
-
mavFtpErrFailerrno
→ const MavFtpErr
-
FailErrno: Command failed, Err number sent back in PayloadHeader.data
1
.
This is a file-system error number understood by the server operating system.
-
mavFtpErrFileexists
→ const MavFtpErr
-
FileExists: File/directory already exists
-
mavFtpErrFilenotfound
→ const MavFtpErr
-
FileNotFound: File/directory not found
-
mavFtpErrFileprotected
→ const MavFtpErr
-
FileProtected: File/directory is write protected
-
mavFtpErrInvaliddatasize
→ const MavFtpErr
-
InvalidDataSize: Payload size is invalid
-
mavFtpErrInvalidsession
→ const MavFtpErr
-
InvalidSession: Session is not currently open
-
mavFtpErrNone
→ const MavFtpErr
-
None: No error
-
mavFtpErrNosessionsavailable
→ const MavFtpErr
-
NoSessionsAvailable: All available sessions are already in use
-
mavFtpErrUnknowncommand
→ const MavFtpErr
-
UnknownCommand: Unknown command / opcode
-
mavFtpOpcodeAck
→ const MavFtpOpcode
-
ACK: ACK response
-
mavFtpOpcodeBurstreadfile
→ const MavFtpOpcode
-
BurstReadFile: Burst download session file
-
mavFtpOpcodeCalcfilecrc
→ const MavFtpOpcode
-
CalcFileCRC32: Calculate CRC32 for file at path
-
mavFtpOpcodeCreatedirectory
→ const MavFtpOpcode
-
CreateDirectory: Creates directory at path
-
mavFtpOpcodeCreatefile
→ const MavFtpOpcode
-
CreateFile: Creates file at path for writing, returns session
-
mavFtpOpcodeListdirectory
→ const MavFtpOpcode
-
ListDirectory. List files and directories in path from offset
-
mavFtpOpcodeNak
→ const MavFtpOpcode
-
NAK: NAK response
-
mavFtpOpcodeNone
→ const MavFtpOpcode
-
None. Ignored, always ACKed
-
mavFtpOpcodeOpenfilero
→ const MavFtpOpcode
-
OpenFileRO: Opens file at path for reading, returns session
-
mavFtpOpcodeOpenfilewo
→ const MavFtpOpcode
-
OpenFileWO: Opens file at path for writing, returns session
-
mavFtpOpcodeReadfile
→ const MavFtpOpcode
-
ReadFile: Reads size bytes from offset in session
-
mavFtpOpcodeRemovedirectory
→ const MavFtpOpcode
-
RemoveDirectory: Removes directory at path. The directory must be empty.
-
mavFtpOpcodeRemovefile
→ const MavFtpOpcode
-
RemoveFile: Remove file at path
-
mavFtpOpcodeRename
→ const MavFtpOpcode
-
Rename: Rename path1 to path2
-
mavFtpOpcodeResetsession
→ const MavFtpOpcode
-
ResetSessions: Terminates all open read sessions
-
mavFtpOpcodeTerminatesession
→ const MavFtpOpcode
-
TerminateSession: Terminates open Read session
-
mavFtpOpcodeTruncatefile
→ const MavFtpOpcode
-
TruncateFile: Truncate file at path to offset length
-
mavFtpOpcodeWritefile
→ const MavFtpOpcode
-
WriteFile: Writes size bytes to offset in session
-
mavGeneratorStatusFlagBatteryOverchargeCurrentFault
→ const MavGeneratorStatusFlag
-
Generator controller detected a high current going into the batteries and shutdown to prevent battery damage.
-
mavGeneratorStatusFlagBatteryUndervoltFault
→ const MavGeneratorStatusFlag
-
Batteries are under voltage (generator will not start).
-
mavGeneratorStatusFlagCharging
→ const MavGeneratorStatusFlag
-
Generator is charging the batteries (generating enough power to charge and provide the load).
-
mavGeneratorStatusFlagCommunicationWarning
→ const MavGeneratorStatusFlag
-
Generator controller having communication problems.
-
mavGeneratorStatusFlagCoolingWarning
→ const MavGeneratorStatusFlag
-
Power electronic or generator cooling system error.
-
mavGeneratorStatusFlagElectronicsFault
→ const MavGeneratorStatusFlag
-
Power electronics experienced a fault and shutdown.
-
mavGeneratorStatusFlagElectronicsOvertempFault
→ const MavGeneratorStatusFlag
-
Power electronics hit the maximum operating temperature and shutdown.
-
mavGeneratorStatusFlagElectronicsOvertempWarning
→ const MavGeneratorStatusFlag
-
Power electronics are near the maximum operating temperature, cooling is insufficient.
-
mavGeneratorStatusFlagGenerating
→ const MavGeneratorStatusFlag
-
Generator is generating power.
-
mavGeneratorStatusFlagIdle
→ const MavGeneratorStatusFlag
-
Generator is idle.
-
mavGeneratorStatusFlagMaintenanceRequired
→ const MavGeneratorStatusFlag
-
Generator requires maintenance.
-
mavGeneratorStatusFlagMaxpower
→ const MavGeneratorStatusFlag
-
Generator is providing the maximum output.
-
mavGeneratorStatusFlagOff
→ const MavGeneratorStatusFlag
-
Generator is off.
-
mavGeneratorStatusFlagOvercurrentFault
→ const MavGeneratorStatusFlag
-
Generator controller exceeded the overcurrent threshold and shutdown to prevent damage.
-
mavGeneratorStatusFlagOvertempFault
→ const MavGeneratorStatusFlag
-
Generator hit the maximum operating temperature and shutdown.
-
mavGeneratorStatusFlagOvertempWarning
→ const MavGeneratorStatusFlag
-
Generator is near the maximum operating temperature, cooling is insufficient.
-
mavGeneratorStatusFlagOvervoltageFault
→ const MavGeneratorStatusFlag
-
Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating.
-
mavGeneratorStatusFlagPowerRailFault
→ const MavGeneratorStatusFlag
-
Generator controller power rail experienced a fault.
-
mavGeneratorStatusFlagPowersourceFault
→ const MavGeneratorStatusFlag
-
The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening.
-
mavGeneratorStatusFlagReady
→ const MavGeneratorStatusFlag
-
Generator is ready to start generating power.
-
mavGeneratorStatusFlagReducedPower
→ const MavGeneratorStatusFlag
-
Generator is operating at a reduced maximum power.
-
mavGeneratorStatusFlagStartInhibited
→ const MavGeneratorStatusFlag
-
Generator start is inhibited by e.g. a safety switch.
-
mavGeneratorStatusFlagWarmingUp
→ const MavGeneratorStatusFlag
-
Generator is not ready to generate yet.
-
mavGotoDoContinue
→ const MavGoto
-
Continue with the next item in mission execution.
-
mavGotoDoHold
→ const MavGoto
-
Hold at the current position.
-
mavGotoHoldAtCurrentPosition
→ const MavGoto
-
Hold at the current position of the system
-
mavGotoHoldAtSpecifiedPosition
→ const MavGoto
-
Hold at the position specified in the parameters of the DO_HOLD action
-
mavLandedStateInAir
→ const MavLandedState
-
MAV is in air
-
mavLandedStateLanding
→ const MavLandedState
-
MAV currently landing
-
mavLandedStateOnGround
→ const MavLandedState
-
MAV is landed (on ground)
-
mavLandedStateTakeoff
→ const MavLandedState
-
MAV currently taking off
-
mavLandedStateUndefined
→ const MavLandedState
-
MAV landed state is unknown
-
mavlinkDataStreamImgBmp
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_BMP
-
mavlinkDataStreamImgJpeg
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_JPEG
-
mavlinkDataStreamImgPgm
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_PGM
-
mavlinkDataStreamImgPng
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_PNG
-
mavlinkDataStreamImgRaw32u
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_RAW32U
-
mavlinkDataStreamImgRaw8u
→ const MavlinkDataStreamType
-
MAVLINK_DATA_STREAM_IMG_RAW8U
-
mavMissionAccepted
→ const MavMissionResult
-
mission accepted OK
-
mavMissionDenied
→ const MavMissionResult
-
Not accepting any mission commands from this communication partner.
-
mavMissionError
→ const MavMissionResult
-
Generic error / not accepting mission commands at all right now.
-
mavMissionInvalid
→ const MavMissionResult
-
One of the parameters has an invalid value.
-
mavMissionInvalidParam1
→ const MavMissionResult
-
param1 has an invalid value.
-
mavMissionInvalidParam2
→ const MavMissionResult
-
param2 has an invalid value.
-
mavMissionInvalidParam3
→ const MavMissionResult
-
param3 has an invalid value.
-
mavMissionInvalidParam4
→ const MavMissionResult
-
param4 has an invalid value.
-
mavMissionInvalidParam5X
→ const MavMissionResult
-
x / param5 has an invalid value.
-
mavMissionInvalidParam6Y
→ const MavMissionResult
-
y / param6 has an invalid value.
-
mavMissionInvalidParam7
→ const MavMissionResult
-
z / param7 has an invalid value.
-
mavMissionInvalidSequence
→ const MavMissionResult
-
Mission item received out of sequence
-
mavMissionNoSpace
→ const MavMissionResult
-
Mission items exceed storage space.
-
mavMissionOperationCancelled
→ const MavMissionResult
-
Current mission operation cancelled (e.g. mission upload, mission download).
-
mavMissionTypeAll
→ const MavMissionType
-
Only used in MISSION_CLEAR_ALL to clear all mission types.
-
mavMissionTypeFence
→ const MavMissionType
-
Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items.
-
mavMissionTypeMission
→ const MavMissionType
-
Items are mission commands for main mission.
-
mavMissionTypeRally
→ const MavMissionType
-
Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items.
-
mavMissionUnsupported
→ const MavMissionResult
-
Command is not supported.
-
mavMissionUnsupportedFrame
→ const MavMissionResult
-
Coordinate frame is not supported.
-
mavModeAutoArmed
→ const MavMode
-
System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
-
mavModeAutoDisarmed
→ const MavMode
-
System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
-
mavModeFlagAutoEnabled
→ const MavModeFlag
-
0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
-
mavModeFlagCustomModeEnabled
→ const MavModeFlag
-
0b00000001 Reserved for future use.
-
mavModeFlagDecodePositionAuto
→ const MavModeFlagDecodePosition
-
Sixth bit: 00000100
-
mavModeFlagDecodePositionCustomMode
→ const MavModeFlagDecodePosition
-
Eighth bit: 00000001
-
mavModeFlagDecodePositionGuided
→ const MavModeFlagDecodePosition
-
Fifth bit: 00001000
-
mavModeFlagDecodePositionHil
→ const MavModeFlagDecodePosition
-
Third bit: 00100000
-
mavModeFlagDecodePositionManual
→ const MavModeFlagDecodePosition
-
Second bit: 01000000
-
mavModeFlagDecodePositionSafety
→ const MavModeFlagDecodePosition
-
First bit: 10000000
-
mavModeFlagDecodePositionStabilize
→ const MavModeFlagDecodePosition
-
Fourth bit: 00010000
-
mavModeFlagDecodePositionTest
→ const MavModeFlagDecodePosition
-
Seventh bit: 00000010
-
mavModeFlagGuidedEnabled
→ const MavModeFlag
-
0b00001000 guided mode enabled, system flies waypoints / mission items.
-
mavModeFlagHilEnabled
→ const MavModeFlag
-
0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
-
mavModeFlagManualInputEnabled
→ const MavModeFlag
-
0b01000000 remote control input is enabled.
-
mavModeFlagSafetyArmed
→ const MavModeFlag
-
0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state.
-
mavModeFlagStabilizeEnabled
→ const MavModeFlag
-
0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
-
mavModeFlagTestEnabled
→ const MavModeFlag
-
0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
-
mavModeGuidedArmed
→ const MavMode
-
System is allowed to be active, under autonomous control, manual setpoint
-
mavModeGuidedDisarmed
→ const MavMode
-
System is allowed to be active, under autonomous control, manual setpoint
-
mavModeManualArmed
→ const MavMode
-
System is allowed to be active, under manual (RC) control, no stabilization
-
mavModeManualDisarmed
→ const MavMode
-
System is allowed to be active, under manual (RC) control, no stabilization
-
mavModePreflight
→ const MavMode
-
System is not ready to fly, booting, calibrating, etc. No flag is set.
-
mavModeStabilizeArmed
→ const MavMode
-
System is allowed to be active, under assisted RC control.
-
mavModeStabilizeDisarmed
→ const MavMode
-
System is allowed to be active, under assisted RC control.
-
mavModeTestArmed
→ const MavMode
-
UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
-
mavModeTestDisarmed
→ const MavMode
-
UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
-
mavMountModeGpsPoint
→ const MavMountMode
-
Load neutral position and start to point to Lat,Lon,Alt
-
mavMountModeHomeLocation
→ const MavMountMode
-
Gimbal tracks home position
-
mavMountModeMavlinkTargeting
→ const MavMountMode
-
Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
-
mavMountModeNeutral
→ const MavMountMode
-
Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.
-
mavMountModeRcTargeting
→ const MavMountMode
-
Load neutral position and start RC Roll,Pitch,Yaw control with stabilization
-
mavMountModeRetract
→ const MavMountMode
-
Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization
-
mavMountModeSysidTarget
→ const MavMountMode
-
Gimbal tracks system with specified system ID
-
mavOdidArmStatusGoodToArm
→ const MavOdidArmStatus
-
Passing arming checks.
-
mavOdidArmStatusPreArmFailGeneric
→ const MavOdidArmStatus
-
Generic arming failure, see error string for details.
-
mavOdidAuthTypeMessageSetSignature
→ const MavOdidAuthType
-
Signature for the entire message set.
-
mavOdidAuthTypeNetworkRemoteId
→ const MavOdidAuthType
-
Authentication is provided by Network Remote ID.
-
mavOdidAuthTypeNone
→ const MavOdidAuthType
-
No authentication type is specified.
-
mavOdidAuthTypeOperatorIdSignature
→ const MavOdidAuthType
-
Signature for the Operator ID.
-
mavOdidAuthTypeSpecificAuthentication
→ const MavOdidAuthType
-
The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO.
-
mavOdidAuthTypeUasIdSignature
→ const MavOdidAuthType
-
Signature for the UAS (Unmanned Aircraft System) ID.
-
mavOdidCategoryEuCertified
→ const MavOdidCategoryEu
-
The category for the UA, according to the EU specification, is the Certified category.
-
mavOdidCategoryEuOpen
→ const MavOdidCategoryEu
-
The category for the UA, according to the EU specification, is the Open category.
-
mavOdidCategoryEuSpecific
→ const MavOdidCategoryEu
-
The category for the UA, according to the EU specification, is the Specific category.
-
mavOdidCategoryEuUndeclared
→ const MavOdidCategoryEu
-
The category for the UA, according to the EU specification, is undeclared.
-
mavOdidClassEuClass0
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 0.
-
mavOdidClassEuClass1
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 1.
-
mavOdidClassEuClass2
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 2.
-
mavOdidClassEuClass3
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 3.
-
mavOdidClassEuClass4
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 4.
-
mavOdidClassEuClass5
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 5.
-
mavOdidClassEuClass6
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is Class 6.
-
mavOdidClassEuUndeclared
→ const MavOdidClassEu
-
The class for the UA, according to the EU specification, is undeclared.
-
mavOdidClassificationTypeEu
→ const MavOdidClassificationType
-
The classification type for the UA follows EU (European Union) specifications.
-
mavOdidClassificationTypeUndeclared
→ const MavOdidClassificationType
-
The classification type for the UA is undeclared.
-
mavOdidDescTypeEmergency
→ const MavOdidDescType
-
Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY.
-
mavOdidDescTypeExtendedStatus
→ const MavOdidDescType
-
Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY.
-
mavOdidDescTypeText
→ const MavOdidDescType
-
Optional free-form text description of the purpose of the flight.
-
mavOdidHeightRefOverGround
→ const MavOdidHeightRef
-
The height field is relative to ground.
-
mavOdidHeightRefOverTakeoff
→ const MavOdidHeightRef
-
The height field is relative to the take-off location.
-
mavOdidHorAcc005nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m.
-
mavOdidHorAcc01nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m.
-
mavOdidHorAcc03nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m.
-
mavOdidHorAcc05nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m.
-
mavOdidHorAcc10Meter
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 10 meter.
-
mavOdidHorAcc10nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km.
-
mavOdidHorAcc1Meter
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 1 meter.
-
mavOdidHorAcc1nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km.
-
mavOdidHorAcc2nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km.
-
mavOdidHorAcc30Meter
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 30 meter.
-
mavOdidHorAcc3Meter
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 3 meter.
-
mavOdidHorAcc4nm
→ const MavOdidHorAcc
-
The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km.
-
mavOdidHorAccUnknown
→ const MavOdidHorAcc
-
The horizontal accuracy is unknown.
-
mavOdidIdTypeCaaRegistrationId
→ const MavOdidIdType
-
CAA (Civil Aviation Authority) registered ID. Format:
ICAO Country Code
.CAA Assigned ID
.
-
mavOdidIdTypeNone
→ const MavOdidIdType
-
No type defined.
-
mavOdidIdTypeSerialNumber
→ const MavOdidIdType
-
Manufacturer Serial Number (ANSI/CTA-2063 format).
-
mavOdidIdTypeSpecificSessionId
→ const MavOdidIdType
-
A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO.
-
mavOdidIdTypeUtmAssignedUuid
→ const MavOdidIdType
-
UTM (Unmanned Traffic Management) assigned UUID (RFC4122).
-
mavOdidOperatorIdTypeCaa
→ const MavOdidOperatorIdType
-
CAA (Civil Aviation Authority) registered operator ID.
-
mavOdidOperatorLocationTypeFixed
→ const MavOdidOperatorLocationType
-
The location/altitude of the operator are fixed values.
-
mavOdidOperatorLocationTypeLiveGnss
→ const MavOdidOperatorLocationType
-
The location/altitude of the operator is dynamic. E.g. based on live GNSS data.
-
mavOdidOperatorLocationTypeTakeoff
→ const MavOdidOperatorLocationType
-
The location/altitude of the operator is the same as the take-off location.
-
mavOdidSpeedAcc03MetersPerSecond
→ const MavOdidSpeedAcc
-
The speed accuracy is smaller than 0.3 meters per second.
-
mavOdidSpeedAcc10MetersPerSecond
→ const MavOdidSpeedAcc
-
The speed accuracy is smaller than 10 meters per second.
-
mavOdidSpeedAcc1MetersPerSecond
→ const MavOdidSpeedAcc
-
The speed accuracy is smaller than 1 meters per second.
-
mavOdidSpeedAcc3MetersPerSecond
→ const MavOdidSpeedAcc
-
The speed accuracy is smaller than 3 meters per second.
-
mavOdidSpeedAccUnknown
→ const MavOdidSpeedAcc
-
The speed accuracy is unknown.
-
mavOdidStatusAirborne
→ const MavOdidStatus
-
The UA is in the air.
-
mavOdidStatusEmergency
→ const MavOdidStatus
-
The UA is having an emergency.
-
mavOdidStatusGround
→ const MavOdidStatus
-
The UA is on the ground.
-
mavOdidStatusRemoteIdSystemFailure
→ const MavOdidStatus
-
The remote ID system is failing or unreliable in some way.
-
mavOdidStatusUndeclared
→ const MavOdidStatus
-
The status of the (UA) Unmanned Aircraft is undefined.
-
mavOdidTimeAcc01Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.1 second.
-
mavOdidTimeAcc02Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.2 second.
-
mavOdidTimeAcc03Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.3 second.
-
mavOdidTimeAcc04Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.4 second.
-
mavOdidTimeAcc05Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.5 second.
-
mavOdidTimeAcc06Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.6 second.
-
mavOdidTimeAcc07Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.7 second.
-
mavOdidTimeAcc08Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.8 second.
-
mavOdidTimeAcc09Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 0.9 second.
-
mavOdidTimeAcc10Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.0 second.
-
mavOdidTimeAcc11Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.1 second.
-
mavOdidTimeAcc12Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.2 second.
-
mavOdidTimeAcc13Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.3 second.
-
mavOdidTimeAcc14Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.4 second.
-
mavOdidTimeAcc15Second
→ const MavOdidTimeAcc
-
The timestamp accuracy is smaller than or equal to 1.5 second.
-
mavOdidTimeAccUnknown
→ const MavOdidTimeAcc
-
The timestamp accuracy is unknown.
-
mavOdidUaTypeAeroplane
→ const MavOdidUaType
-
Aeroplane/Airplane. Fixed wing.
-
mavOdidUaTypeAirship
→ const MavOdidUaType
-
Airship. E.g. a blimp.
-
mavOdidUaTypeCaptiveBalloon
→ const MavOdidUaType
-
Captive Balloon.
-
mavOdidUaTypeFreeBalloon
→ const MavOdidUaType
-
Free Balloon.
-
mavOdidUaTypeFreeFallParachute
→ const MavOdidUaType
-
Free Fall/Parachute (unpowered).
-
mavOdidUaTypeGlider
→ const MavOdidUaType
-
Glider.
-
mavOdidUaTypeGroundObstacle
→ const MavOdidUaType
-
Ground Obstacle.
-
mavOdidUaTypeGyroplane
→ const MavOdidUaType
-
Gyroplane.
-
mavOdidUaTypeHelicopterOrMultirotor
→ const MavOdidUaType
-
Helicopter or multirotor.
-
mavOdidUaTypeHybridLift
→ const MavOdidUaType
-
VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically.
-
mavOdidUaTypeKite
→ const MavOdidUaType
-
Kite.
-
mavOdidUaTypeNone
→ const MavOdidUaType
-
No UA (Unmanned Aircraft) type defined.
-
mavOdidUaTypeOrnithopter
→ const MavOdidUaType
-
Ornithopter.
-
mavOdidUaTypeOther
→ const MavOdidUaType
-
Other type of aircraft not listed earlier.
-
mavOdidUaTypeRocket
→ const MavOdidUaType
-
Rocket.
-
mavOdidUaTypeTetheredPoweredAircraft
→ const MavOdidUaType
-
Tethered powered aircraft.
-
mavOdidVerAcc10Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 10 meter.
-
mavOdidVerAcc150Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 150 meter.
-
mavOdidVerAcc1Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 1 meter.
-
mavOdidVerAcc25Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 25 meter.
-
mavOdidVerAcc3Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 3 meter.
-
mavOdidVerAcc45Meter
→ const MavOdidVerAcc
-
The vertical accuracy is smaller than 45 meter.
-
mavOdidVerAccUnknown
→ const MavOdidVerAcc
-
The vertical accuracy is unknown.
-
mavParamExtTypeCustom
→ const MavParamExtType
-
Custom Type
-
mavParamExtTypeInt16
→ const MavParamExtType
-
16-bit signed integer
-
mavParamExtTypeInt32
→ const MavParamExtType
-
32-bit signed integer
-
mavParamExtTypeInt64
→ const MavParamExtType
-
64-bit signed integer
-
mavParamExtTypeInt8
→ const MavParamExtType
-
8-bit signed integer
-
mavParamExtTypeReal32
→ const MavParamExtType
-
32-bit floating-point
-
mavParamExtTypeReal64
→ const MavParamExtType
-
64-bit floating-point
-
mavParamExtTypeUint16
→ const MavParamExtType
-
16-bit unsigned integer
-
mavParamExtTypeUint32
→ const MavParamExtType
-
32-bit unsigned integer
-
mavParamExtTypeUint64
→ const MavParamExtType
-
64-bit unsigned integer
-
mavParamExtTypeUint8
→ const MavParamExtType
-
8-bit unsigned integer
-
mavParamTypeInt16
→ const MavParamType
-
16-bit signed integer
-
mavParamTypeInt32
→ const MavParamType
-
32-bit signed integer
-
mavParamTypeInt64
→ const MavParamType
-
64-bit signed integer
-
mavParamTypeInt8
→ const MavParamType
-
8-bit signed integer
-
mavParamTypeReal32
→ const MavParamType
-
32-bit floating-point
-
mavParamTypeReal64
→ const MavParamType
-
64-bit floating-point
-
mavParamTypeUint16
→ const MavParamType
-
16-bit unsigned integer
-
mavParamTypeUint32
→ const MavParamType
-
32-bit unsigned integer
-
mavParamTypeUint64
→ const MavParamType
-
64-bit unsigned integer
-
mavParamTypeUint8
→ const MavParamType
-
8-bit unsigned integer
-
mavPfsCmdClearAll
→ const MavPreflightStorageAction
-
Clear all parameters in storage
-
mavPfsCmdClearSpecific
→ const MavPreflightStorageAction
-
Clear specific parameters in storage
-
mavPfsCmdDoNothing
→ const MavPreflightStorageAction
-
do nothing
-
mavPfsCmdReadAll
→ const MavPreflightStorageAction
-
Read all parameters from storage
-
mavPfsCmdReadSpecific
→ const MavPreflightStorageAction
-
Read specific parameters from storage
-
mavPfsCmdWriteAll
→ const MavPreflightStorageAction
-
Write all parameters to storage
-
mavPfsCmdWriteSpecific
→ const MavPreflightStorageAction
-
Write specific parameters to storage
-
mavPowerStatusBrickValid
→ const MavPowerStatus
-
main brick power supply valid
-
mavPowerStatusChanged
→ const MavPowerStatus
-
Power status has changed since boot
-
mavPowerStatusPeriphHipowerOvercurrent
→ const MavPowerStatus
-
hi-power peripheral supply is in over-current state
-
mavPowerStatusPeriphOvercurrent
→ const MavPowerStatus
-
peripheral supply is in over-current state
-
mavPowerStatusServoValid
→ const MavPowerStatus
-
main servo power supply valid for FMU
-
mavPowerStatusUsbConnected
→ const MavPowerStatus
-
USB power is connected
-
mavProtocolCapabilityCommandInt
→ const MavProtocolCapability
-
Autopilot supports COMMAND_INT scaled integer message type.
-
mavProtocolCapabilityCompassCalibration
→ const MavProtocolCapability
-
Autopilot supports onboard compass calibration.
-
mavProtocolCapabilityFlightTermination
→ const MavProtocolCapability
-
Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination).
-
mavProtocolCapabilityFtp
→ const MavProtocolCapability
-
Autopilot supports the File Transfer Protocol v1: https://mavlink.io/en/services/ftp.html.
-
mavProtocolCapabilityMavlink2
→ const MavProtocolCapability
-
Autopilot supports MAVLink version 2.
-
mavProtocolCapabilityMissionFence
→ const MavProtocolCapability
-
Autopilot supports mission fence protocol.
-
mavProtocolCapabilityMissionFloat
→ const MavProtocolCapability
-
Autopilot supports the MISSION_ITEM float message type.
Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead.
-
mavProtocolCapabilityMissionInt
→ const MavProtocolCapability
-
Autopilot supports MISSION_ITEM_INT scaled integer message type.
Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated).
-
mavProtocolCapabilityMissionRally
→ const MavProtocolCapability
-
Autopilot supports mission rally point protocol.
-
mavProtocolCapabilityParamEncodeBytewise
→ const MavProtocolCapability
-
Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding.
Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported.
-
mavProtocolCapabilityParamEncodeCCast
→ const MavProtocolCapability
-
Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding.
Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported.
-
mavProtocolCapabilityParamFloat
→ const MavProtocolCapability
-
Autopilot supports the new param float message type.
-
mavProtocolCapabilityReserved2
→ const MavProtocolCapability
-
Reserved for future use.
-
mavProtocolCapabilityReserved3
→ const MavProtocolCapability
-
Reserved for future use.
-
mavProtocolCapabilitySetAttitudeTarget
→ const MavProtocolCapability
-
Autopilot supports commanding attitude offboard.
-
mavProtocolCapabilitySetPositionTargetGlobalInt
→ const MavProtocolCapability
-
Autopilot supports commanding position and velocity targets in global scaled integers.
-
mavProtocolCapabilitySetPositionTargetLocalNed
→ const MavProtocolCapability
-
Autopilot supports commanding position and velocity targets in local NED frame.
-
mavProtocolCapabilityTerrain
→ const MavProtocolCapability
-
Autopilot supports terrain protocol / data handling.
-
mavResultAccepted
→ const MavResult
-
Command is valid (is supported and has valid parameters), and was executed.
-
mavResultCancelled
→ const MavResult
-
Command has been cancelled (as a result of receiving a COMMAND_CANCEL message).
-
mavResultCommandIntOnly
→ const MavResult
-
Command is only accepted when sent as a COMMAND_INT.
-
mavResultCommandLongOnly
→ const MavResult
-
Command is only accepted when sent as a COMMAND_LONG.
-
mavResultCommandUnsupportedMavFrame
→ const MavResult
-
Command is invalid because a frame is required and the specified frame is not supported.
-
mavResultDenied
→ const MavResult
-
Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work.
-
mavResultFailed
→ const MavResult
-
Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc.
-
mavResultInProgress
→ const MavResult
-
Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation.
-
mavResultTemporarilyRejected
→ const MavResult
-
Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work.
-
mavResultUnsupported
→ const MavResult
-
Command is not supported (unknown).
-
mavRoiLocation
→ const MavRoi
-
Point toward fixed location.
-
mavRoiNone
→ const MavRoi
-
No region of interest.
-
mavRoiTarget
→ const MavRoi
-
Point toward of given id.
-
mavRoiWpindex
→ const MavRoi
-
Point toward given waypoint.
-
mavRoiWpnext
→ const MavRoi
-
Point toward next waypoint, with optional pitch/roll/yaw offset.
-
mavSensorRotationCustom
→ const MavSensorOrientation
-
Custom orientation
-
mavSensorRotationNone
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 0
-
mavSensorRotationPitch180
→ const MavSensorOrientation
-
Roll: 0, Pitch: 180, Yaw: 0
-
mavSensorRotationPitch180Yaw270
→ const MavSensorOrientation
-
Roll: 0, Pitch: 180, Yaw: 270
-
mavSensorRotationPitch180Yaw90
→ const MavSensorOrientation
-
Roll: 0, Pitch: 180, Yaw: 90
-
mavSensorRotationPitch270
→ const MavSensorOrientation
-
Roll: 0, Pitch: 270, Yaw: 0
-
mavSensorRotationPitch315
→ const MavSensorOrientation
-
Pitch: 315
-
mavSensorRotationPitch90
→ const MavSensorOrientation
-
Roll: 0, Pitch: 90, Yaw: 0
-
mavSensorRotationRoll180
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 0
-
mavSensorRotationRoll180Pitch270
→ const MavSensorOrientation
-
Roll: 180, Pitch: 270, Yaw: 0
-
mavSensorRotationRoll180Pitch90
→ const MavSensorOrientation
-
Roll: 180, Pitch: 90, Yaw: 0
-
mavSensorRotationRoll180Yaw135
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 135
-
mavSensorRotationRoll180Yaw225
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 225
-
mavSensorRotationRoll180Yaw270
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 270
-
mavSensorRotationRoll180Yaw315
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 315
-
mavSensorRotationRoll180Yaw45
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 45
-
mavSensorRotationRoll180Yaw90
→ const MavSensorOrientation
-
Roll: 180, Pitch: 0, Yaw: 90
-
mavSensorRotationRoll270
→ const MavSensorOrientation
-
Roll: 270, Pitch: 0, Yaw: 0
-
mavSensorRotationRoll270Pitch180
→ const MavSensorOrientation
-
Roll: 270, Pitch: 180, Yaw: 0
-
mavSensorRotationRoll270Pitch270
→ const MavSensorOrientation
-
Roll: 270, Pitch: 270, Yaw: 0
-
mavSensorRotationRoll270Pitch90
→ const MavSensorOrientation
-
Roll: 270, Pitch: 90, Yaw: 0
-
mavSensorRotationRoll270Yaw135
→ const MavSensorOrientation
-
Roll: 270, Pitch: 0, Yaw: 135
-
mavSensorRotationRoll270Yaw45
→ const MavSensorOrientation
-
Roll: 270, Pitch: 0, Yaw: 45
-
mavSensorRotationRoll270Yaw90
→ const MavSensorOrientation
-
Roll: 270, Pitch: 0, Yaw: 90
-
mavSensorRotationRoll90
→ const MavSensorOrientation
-
Roll: 90, Pitch: 0, Yaw: 0
-
mavSensorRotationRoll90Pitch180
→ const MavSensorOrientation
-
Roll: 90, Pitch: 180, Yaw: 0
-
mavSensorRotationRoll90Pitch180Yaw90
→ const MavSensorOrientation
-
Roll: 90, Pitch: 180, Yaw: 90
-
mavSensorRotationRoll90Pitch270
→ const MavSensorOrientation
-
Roll: 90, Pitch: 270, Yaw: 0
-
mavSensorRotationRoll90Pitch315
→ const MavSensorOrientation
-
Roll: 90, Pitch: 315
-
mavSensorRotationRoll90Pitch68Yaw293
→ const MavSensorOrientation
-
Roll: 90, Pitch: 68, Yaw: 293
-
mavSensorRotationRoll90Pitch90
→ const MavSensorOrientation
-
Roll: 90, Pitch: 90, Yaw: 0
-
mavSensorRotationRoll90Yaw135
→ const MavSensorOrientation
-
Roll: 90, Pitch: 0, Yaw: 135
-
mavSensorRotationRoll90Yaw270
→ const MavSensorOrientation
-
Roll: 90, Pitch: 0, Yaw: 270
-
mavSensorRotationRoll90Yaw45
→ const MavSensorOrientation
-
Roll: 90, Pitch: 0, Yaw: 45
-
mavSensorRotationRoll90Yaw90
→ const MavSensorOrientation
-
Roll: 90, Pitch: 0, Yaw: 90
-
mavSensorRotationYaw135
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 135
-
mavSensorRotationYaw180
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 180
-
mavSensorRotationYaw225
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 225
-
mavSensorRotationYaw270
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 270
-
mavSensorRotationYaw315
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 315
-
mavSensorRotationYaw45
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 45
-
mavSensorRotationYaw90
→ const MavSensorOrientation
-
Roll: 0, Pitch: 0, Yaw: 90
-
mavSeverityAlert
→ const MavSeverity
-
Action should be taken immediately. Indicates error in non-critical systems.
-
mavSeverityCritical
→ const MavSeverity
-
Action must be taken immediately. Indicates failure in a primary system.
-
mavSeverityDebug
→ const MavSeverity
-
Useful non-operational messages that can assist in debugging. These should not occur during normal operation.
-
mavSeverityEmergency
→ const MavSeverity
-
System is unusable. This is a "panic" condition.
-
mavSeverityError
→ const MavSeverity
-
Indicates an error in secondary/redundant systems.
-
mavSeverityInfo
→ const MavSeverity
-
Normal operational messages. Useful for logging. No action is required for these messages.
-
mavSeverityNotice
→ const MavSeverity
-
An unusual event has occurred, though not an error condition. This should be investigated for the root cause.
-
mavSeverityWarning
→ const MavSeverity
-
Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.
-
mavStateActive
→ const MavState
-
System is active and might be already airborne. Motors are engaged.
-
mavStateBoot
→ const MavState
-
System is booting up.
-
mavStateCalibrating
→ const MavState
-
System is calibrating and not flight-ready.
-
mavStateCritical
→ const MavState
-
System is in a non-normal flight mode (failsafe). It can however still navigate.
-
mavStateEmergency
→ const MavState
-
System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down.
-
mavStateFlightTermination
→ const MavState
-
System is terminating itself (failsafe or commanded).
-
mavStatePoweroff
→ const MavState
-
System just initialized its power-down sequence, will shut down now.
-
mavStateStandby
→ const MavState
-
System is grounded and on standby. It can be launched any time.
-
mavStateUninit
→ const MavState
-
Uninitialized system, state is unknown.
-
mavSysStatusAhrs
→ const MavSysStatusSensor
-
0x200000 AHRS subsystem health
-
mavSysStatusExtensionUsed
→ const MavSysStatusSensor
-
0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)
-
mavSysStatusGeofence
→ const MavSysStatusSensor
-
0x100000 geofence
-
mavSysStatusLogging
→ const MavSysStatusSensor
-
0x1000000 Logging
-
mavSysStatusObstacleAvoidance
→ const MavSysStatusSensor
-
0x20000000 Avoidance/collision prevention
-
mavSysStatusPrearmCheck
→ const MavSysStatusSensor
-
0x10000000 pre-arm check status. Always healthy when armed
-
mavSysStatusRecoverySystem
→ const MavSysStatusSensorExtended
-
0x01 Recovery system (parachute, balloon, retracts etc)
-
mavSysStatusReverseMotor
→ const MavSysStatusSensor
-
0x800000 Motors are reversed
-
mavSysStatusSensor3dAccel
→ const MavSysStatusSensor
-
0x02 3D accelerometer
-
mavSysStatusSensor3dAccel2
→ const MavSysStatusSensor
-
0x40000 2nd 3D accelerometer
-
mavSysStatusSensor3dGyro
→ const MavSysStatusSensor
-
0x01 3D gyro
-
mavSysStatusSensor3dGyro2
→ const MavSysStatusSensor
-
0x20000 2nd 3D gyro
-
mavSysStatusSensor3dMag
→ const MavSysStatusSensor
-
0x04 3D magnetometer
-
mavSysStatusSensor3dMag2
→ const MavSysStatusSensor
-
0x80000 2nd 3D magnetometer
-
mavSysStatusSensorAbsolutePressure
→ const MavSysStatusSensor
-
0x08 absolute pressure
-
mavSysStatusSensorAngularRateControl
→ const MavSysStatusSensor
-
0x400 3D angular rate control
-
mavSysStatusSensorAttitudeStabilization
→ const MavSysStatusSensor
-
0x800 attitude stabilization
-
mavSysStatusSensorBattery
→ const MavSysStatusSensor
-
0x2000000 Battery
-
mavSysStatusSensorDifferentialPressure
→ const MavSysStatusSensor
-
0x10 differential pressure
-
mavSysStatusSensorExternalGroundTruth
→ const MavSysStatusSensor
-
0x200 external ground truth (Vicon or Leica)
-
mavSysStatusSensorGps
→ const MavSysStatusSensor
-
0x20 GPS
-
mavSysStatusSensorLaserPosition
→ const MavSysStatusSensor
-
0x100 laser based position
-
mavSysStatusSensorMotorOutputs
→ const MavSysStatusSensor
-
0x8000 motor outputs / control
-
mavSysStatusSensorOpticalFlow
→ const MavSysStatusSensor
-
0x40 optical flow
-
mavSysStatusSensorPropulsion
→ const MavSysStatusSensor
-
0x40000000 propulsion (actuator, esc, motor or propellor)
-
mavSysStatusSensorProximity
→ const MavSysStatusSensor
-
0x4000000 Proximity
-
mavSysStatusSensorRcReceiver
→ const MavSysStatusSensor
-
0x10000 RC receiver
-
mavSysStatusSensorSatcom
→ const MavSysStatusSensor
-
0x8000000 Satellite Communication
-
mavSysStatusSensorVisionPosition
→ const MavSysStatusSensor
-
0x80 computer vision position
-
mavSysStatusSensorXyPositionControl
→ const MavSysStatusSensor
-
0x4000 x/y position control
-
mavSysStatusSensorYawPosition
→ const MavSysStatusSensor
-
0x1000 yaw position
-
mavSysStatusSensorZAltitudeControl
→ const MavSysStatusSensor
-
0x2000 z/altitude control
-
mavSysStatusTerrain
→ const MavSysStatusSensor
-
0x400000 Terrain subsystem health
-
mavTunnelPayloadTypeStorm32Reserved0
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved1
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved2
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved3
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved4
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved5
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved6
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved7
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved8
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeStorm32Reserved9
→ const MavTunnelPayloadType
-
Registered for STorM32 gimbal controller.
-
mavTunnelPayloadTypeUnknown
→ const MavTunnelPayloadType
-
Encoding of payload unknown.
-
mavTypeAdsb
→ const MavType
-
ADSB system
-
mavTypeAirship
→ const MavType
-
Airship, controlled
-
mavTypeAntennaTracker
→ const MavType
-
Ground installation
-
mavTypeBattery
→ const MavType
-
Battery
-
mavTypeCamera
→ const MavType
-
Camera
-
mavTypeChargingStation
→ const MavType
-
Charging station
-
mavTypeCoaxial
→ const MavType
-
Coaxial helicopter
-
mavTypeDecarotor
→ const MavType
-
Decarotor
-
mavTypeDodecarotor
→ const MavType
-
Dodecarotor
-
mavTypeFixedWing
→ const MavType
-
Fixed wing aircraft.
-
mavTypeFlappingWing
→ const MavType
-
Flapping wing
-
mavTypeFlarm
→ const MavType
-
FLARM collision avoidance system
-
mavTypeFreeBalloon
→ const MavType
-
Free balloon, uncontrolled
-
mavTypeGcs
→ const MavType
-
Operator control unit / ground control station
-
mavTypeGeneric
→ const MavType
-
Generic micro air vehicle
-
mavTypeGenericMultirotor
→ const MavType
-
Generic multirotor that does not fit into a specific type or whose type is unknown
-
mavTypeGimbal
→ const MavType
-
Gimbal
-
mavTypeGps
→ const MavType
-
GPS
-
mavTypeGroundRover
→ const MavType
-
Ground rover
-
mavTypeHelicopter
→ const MavType
-
Normal helicopter with tail rotor.
-
mavTypeHexarotor
→ const MavType
-
Hexarotor
-
mavTypeImu
→ const MavType
-
IMU
-
mavTypeKite
→ const MavType
-
Kite
-
mavTypeLog
→ const MavType
-
Log
-
mavTypeOctorotor
→ const MavType
-
Octorotor
-
mavTypeOdid
→ const MavType
-
Open Drone ID. See https://mavlink.io/en/services/opendroneid.html.
-
mavTypeOnboardController
→ const MavType
-
Onboard companion controller
-
mavTypeOsd
→ const MavType
-
OSD
-
mavTypeParachute
→ const MavType
-
Parachute
-
mavTypeParafoil
→ const MavType
-
Steerable, nonrigid airfoil
-
mavTypeQuadrotor
→ const MavType
-
Quadrotor
-
mavTypeRocket
→ const MavType
-
Rocket
-
mavTypeServo
→ const MavType
-
Servo
-
mavTypeSubmarine
→ const MavType
-
Submarine
-
mavTypeSurfaceBoat
→ const MavType
-
Surface vessel, boat, ship
-
mavTypeTricopter
→ const MavType
-
Tricopter
-
mavTypeVtolFixedrotor
→ const MavType
-
VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases.
-
mavTypeVtolReserved5
→ const MavType
-
VTOL reserved 5
-
mavTypeVtolTailsitter
→ const MavType
-
Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate.
-
mavTypeVtolTailsitterDuorotor
→ const MavType
-
Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR.
-
mavTypeVtolTailsitterQuadrotor
→ const MavType
-
Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR.
-
mavTypeVtolTiltrotor
→ const MavType
-
Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight.
-
mavTypeVtolTiltwing
→ const MavType
-
Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode.
-
mavTypeWinch
→ const MavType
-
Winch
-
mavVtolStateFw
→ const MavVtolState
-
VTOL is in fixed-wing state
-
mavVtolStateMc
→ const MavVtolState
-
VTOL is in multicopter state
-
mavVtolStateTransitionToFw
→ const MavVtolState
-
VTOL is in transition from multicopter to fixed-wing
-
mavVtolStateTransitionToMc
→ const MavVtolState
-
VTOL is in transition from fixed-wing to multicopter
-
mavVtolStateUndefined
→ const MavVtolState
-
MAV is not configured as VTOL
-
mavWinchStatusAbandonLine
→ const MavWinchStatusFlag
-
Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold.
-
mavWinchStatusArresting
→ const MavWinchStatusFlag
-
Winch is arresting payload descent.
-
mavWinchStatusClutchEngaged
→ const MavWinchStatusFlag
-
Winch clutch is engaged allowing motor to move freely.
-
mavWinchStatusDropping
→ const MavWinchStatusFlag
-
Winch is gravity dropping payload.
-
mavWinchStatusFullyRetracted
→ const MavWinchStatusFlag
-
Winch line is fully retracted
-
mavWinchStatusGroundSense
→ const MavWinchStatusFlag
-
Winch is using torque measurements to sense the ground.
-
mavWinchStatusHealthy
→ const MavWinchStatusFlag
-
Winch is healthy
-
mavWinchStatusLoadLine
→ const MavWinchStatusFlag
-
Winch is spooling on line.
-
mavWinchStatusLoadPayload
→ const MavWinchStatusFlag
-
Winch is loading a payload.
-
mavWinchStatusLocked
→ const MavWinchStatusFlag
-
Winch is locked by locking mechanism.
-
mavWinchStatusLocking
→ const MavWinchStatusFlag
-
Winch is engaging the locking mechanism.
-
mavWinchStatusMoving
→ const MavWinchStatusFlag
-
Winch motor is moving
-
mavWinchStatusRedeliver
→ const MavWinchStatusFlag
-
Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING.
-
mavWinchStatusRetracting
→ const MavWinchStatusFlag
-
Winch is returning to the fully retracted position.
-
missionReadPersistent
→ const PreflightStorageMissionAction
-
Read current mission data from persistent storage
-
missionResetDefault
→ const PreflightStorageMissionAction
-
Erase all mission data stored on the vehicle (both persistent and volatile storage)
-
missionStateActive
→ const MissionState
-
Mission is active, and will execute mission items when in auto mode.
-
missionStateComplete
→ const MissionState
-
Mission has executed all mission items.
-
missionStateNoMission
→ const MissionState
-
No mission on the vehicle.
-
missionStateNotStarted
→ const MissionState
-
Mission has not started. This is the case after a mission has uploaded but not yet started executing.
-
missionStatePaused
→ const MissionState
-
Mission is paused when in auto mode.
-
missionStateUnknown
→ const MissionState
-
The mission status reporting is not supported.
-
missionWritePersistent
→ const PreflightStorageMissionAction
-
Write current mission data to persistent storage
-
motorTestCompassCal
→ const MotorTestThrottleType
-
Per-motor compass calibration test.
-
motorTestOrderBoard
→ const MotorTestOrder
-
Motor numbers are specified as the output as labeled on the board.
-
motorTestOrderDefault
→ const MotorTestOrder
-
Default autopilot motor test method.
-
motorTestOrderSequence
→ const MotorTestOrder
-
Motor numbers are specified as their index in a predefined vehicle-specific sequence.
-
motorTestThrottlePercent
→ const MotorTestThrottleType
-
Throttle as a percentage (0 ~ 100)
-
motorTestThrottlePilot
→ const MotorTestThrottleType
-
Throttle pass-through from pilot's transmitter.
-
motorTestThrottlePwm
→ const MotorTestThrottleType
-
Throttle as an absolute PWM value (normally in range of 1000~2000).
-
navVtolLandOptionsDefault
→ const NavVtolLandOptions
-
Default autopilot landing behaviour.
-
navVtolLandOptionsFwDescent
→ const NavVtolLandOptions
-
Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground.
The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.).
-
navVtolLandOptionsHoverDescent
→ const NavVtolLandOptions
-
Land in multicopter mode on reaching the landing coordinates (the whole landing is by "hover descent").
-
orbitYawBehaviourHoldFrontTangentToCircle
→ const OrbitYawBehaviour
-
Vehicle front follows flight path (tangential to circle).
-
orbitYawBehaviourHoldFrontToCircleCenter
→ const OrbitYawBehaviour
-
Vehicle front points to the center (default).
-
orbitYawBehaviourHoldInitialHeading
→ const OrbitYawBehaviour
-
Vehicle front holds heading when message received.
-
orbitYawBehaviourRcControlled
→ const OrbitYawBehaviour
-
Yaw controlled by RC input.
-
orbitYawBehaviourUncontrolled
→ const OrbitYawBehaviour
-
Yaw uncontrolled.
-
parachuteDisable
→ const ParachuteAction
-
Disable auto-release of parachute (i.e. release triggered by crash detectors).
-
parachuteEnable
→ const ParachuteAction
-
Enable auto-release of parachute.
-
parachuteRelease
→ const ParachuteAction
-
Release parachute and kill motors.
-
paramAckAccepted
→ const ParamAck
-
Parameter value ACCEPTED and SET
-
paramAckFailed
→ const ParamAck
-
Parameter failed to set
-
paramAckInProgress
→ const ParamAck
-
Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent.
-
paramAckValueUnsupported
→ const ParamAck
-
Parameter value UNKNOWN/UNSUPPORTED
-
paramReadPersistent
→ const PreflightStorageParameterAction
-
Read all parameters from persistent storage. Replaces values in volatile storage.
-
paramResetAllDefault
→ const PreflightStorageParameterAction
-
Reset all parameters, including operation counters, to default values
-
paramResetConfigDefault
→ const PreflightStorageParameterAction
-
Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics.
-
paramResetSensorDefault
→ const PreflightStorageParameterAction
-
Reset only sensor calibration parameters to factory defaults (or firmware default if not available)
-
paramWritePersistent
→ const PreflightStorageParameterAction
-
Write all parameter values to persistent storage (flash/EEPROM)
-
positionTargetTypemaskAxIgnore
→ const PositionTargetTypemask
-
Ignore acceleration x
-
positionTargetTypemaskAyIgnore
→ const PositionTargetTypemask
-
Ignore acceleration y
-
positionTargetTypemaskAzIgnore
→ const PositionTargetTypemask
-
Ignore acceleration z
-
positionTargetTypemaskForceSet
→ const PositionTargetTypemask
-
Use force instead of acceleration
-
positionTargetTypemaskVxIgnore
→ const PositionTargetTypemask
-
Ignore velocity x
-
positionTargetTypemaskVyIgnore
→ const PositionTargetTypemask
-
Ignore velocity y
-
positionTargetTypemaskVzIgnore
→ const PositionTargetTypemask
-
Ignore velocity z
-
positionTargetTypemaskXIgnore
→ const PositionTargetTypemask
-
Ignore position x
-
positionTargetTypemaskYawIgnore
→ const PositionTargetTypemask
-
Ignore yaw
-
positionTargetTypemaskYawRateIgnore
→ const PositionTargetTypemask
-
Ignore yaw rate
-
positionTargetTypemaskYIgnore
→ const PositionTargetTypemask
-
Ignore position y
-
positionTargetTypemaskZIgnore
→ const PositionTargetTypemask
-
Ignore position z
-
precisionLandModeDisabled
→ const PrecisionLandMode
-
Normal (non-precision) landing.
-
precisionLandModeOpportunistic
→ const PrecisionLandMode
-
Use precision landing if beacon detected when land command accepted, otherwise land normally.
-
precisionLandModeRequired
→ const PrecisionLandMode
-
Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found).
-
rcTypeSpektrumDsm2
→ const RcType
-
Spektrum DSM2
-
rcTypeSpektrumDsmx
→ const RcType
-
Spektrum DSMX
-
rtkBaselineCoordinateSystemEcef
→ const RtkBaselineCoordinateSystem
-
Earth-centered, Earth-fixed
-
rtkBaselineCoordinateSystemNed
→ const RtkBaselineCoordinateSystem
-
RTK basestation centered, north, east, down
-
safetySwitchStateDangerous
→ const SafetySwitchState
-
Safety switch is NOT engaged and motors, propellers and other actuators should be considered active.
-
safetySwitchStateSafe
→ const SafetySwitchState
-
Safety switch is engaged and vehicle should be safe to approach.
-
serialControlDevGps1
→ const SerialControlDev
-
First GPS port
-
serialControlDevGps2
→ const SerialControlDev
-
Second GPS port
-
serialControlDevShell
→ const SerialControlDev
-
system shell
-
serialControlDevTelem1
→ const SerialControlDev
-
First telemetry port
-
serialControlDevTelem2
→ const SerialControlDev
-
Second telemetry port
-
serialControlFlagBlocking
→ const SerialControlFlag
-
Block on writes to the serial port
-
serialControlFlagExclusive
→ const SerialControlFlag
-
Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set
-
serialControlFlagMulti
→ const SerialControlFlag
-
Send multiple replies until port is drained
-
serialControlFlagReply
→ const SerialControlFlag
-
Set if this is a reply
-
serialControlFlagRespond
→ const SerialControlFlag
-
Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message
-
serialControlSerial0
→ const SerialControlDev
-
SERIAL0
-
serialControlSerial1
→ const SerialControlDev
-
SERIAL1
-
serialControlSerial2
→ const SerialControlDev
-
SERIAL2
-
serialControlSerial3
→ const SerialControlDev
-
SERIAL3
-
serialControlSerial4
→ const SerialControlDev
-
SERIAL4
-
serialControlSerial5
→ const SerialControlDev
-
SERIAL5
-
serialControlSerial6
→ const SerialControlDev
-
SERIAL6
-
serialControlSerial7
→ const SerialControlDev
-
SERIAL7
-
serialControlSerial8
→ const SerialControlDev
-
SERIAL8
-
serialControlSerial9
→ const SerialControlDev
-
SERIAL9
-
speedTypeAirspeed
→ const SpeedType
-
Airspeed
-
speedTypeClimbSpeed
→ const SpeedType
-
Climb speed
-
speedTypeDescentSpeed
→ const SpeedType
-
Descent speed
-
speedTypeGroundspeed
→ const SpeedType
-
Groundspeed
-
storageStatusEmpty
→ const StorageStatus
-
Storage is missing (no microSD card loaded for example.)
-
storageStatusNotSupported
→ const StorageStatus
-
Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored.
-
storageStatusReady
→ const StorageStatus
-
Storage present and ready.
-
storageStatusUnformatted
→ const StorageStatus
-
Storage present but unformatted.
-
storageTypeCf
→ const StorageType
-
Storage type is CFast.
-
storageTypeCfe
→ const StorageType
-
Storage type is CFexpress.
-
storageTypeHd
→ const StorageType
-
Storage type is HD mass storage type.
-
storageTypeMicrosd
→ const StorageType
-
Storage type is microSD card.
-
storageTypeOther
→ const StorageType
-
Storage type is other, not listed type.
-
storageTypeSd
→ const StorageType
-
Storage type is SD card.
-
storageTypeUnknown
→ const StorageType
-
Storage type is not known.
-
storageTypeUsbStick
→ const StorageType
-
Storage type is USB device.
-
storageTypeXqd
→ const StorageType
-
Storage type is XQD.
-
storageUsageFlagLogs
→ const StorageUsageFlag
-
Storage for saving logs.
-
storageUsageFlagPhoto
→ const StorageUsageFlag
-
Storage for saving photos.
-
storageUsageFlagSet
→ const StorageUsageFlag
-
Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported).
-
storageUsageFlagVideo
→ const StorageUsageFlag
-
Storage for saving videos.
-
tuneFormatMmlModern
→ const TuneFormat
-
Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML.
-
tuneFormatQbasic11
→ const TuneFormat
-
Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm.
-
uavcanNodeHealthCritical
→ const UavcanNodeHealth
-
The node has suffered a fatal malfunction.
-
uavcanNodeHealthError
→ const UavcanNodeHealth
-
The node has encountered a major failure.
-
uavcanNodeHealthOk
→ const UavcanNodeHealth
-
The node is functioning properly.
-
uavcanNodeHealthWarning
→ const UavcanNodeHealth
-
A critical parameter went out of range or the node has encountered a minor failure.
-
uavcanNodeModeInitialization
→ const UavcanNodeMode
-
The node is initializing; this mode is entered immediately after startup.
-
uavcanNodeModeMaintenance
→ const UavcanNodeMode
-
The node is under maintenance.
-
uavcanNodeModeOffline
→ const UavcanNodeMode
-
The node is no longer available online.
-
uavcanNodeModeOperational
→ const UavcanNodeMode
-
The node is performing its primary functions.
-
uavcanNodeModeSoftwareUpdate
→ const UavcanNodeMode
-
The node is in the process of updating its software.
-
underWay
→ const AisNavStatus
-
Under way using engine.
-
utmDataAvailFlagsAltitudeAvailable
→ const UtmDataAvailFlags
-
The fields alt and v_acc contain valid data.
-
utmDataAvailFlagsHorizontalVeloAvailable
→ const UtmDataAvailFlags
-
The fields vx and vy contain valid data.
-
utmDataAvailFlagsNextWaypointAvailable
→ const UtmDataAvailFlags
-
The fields next_lat, next_lon and next_alt contain valid data.
-
utmDataAvailFlagsPositionAvailable
→ const UtmDataAvailFlags
-
The fields lat, lon and h_acc contain valid data.
-
utmDataAvailFlagsRelativeAltitudeAvailable
→ const UtmDataAvailFlags
-
The field relative_alt contains valid data.
-
utmDataAvailFlagsTimeValid
→ const UtmDataAvailFlags
-
The field time contains valid data.
-
utmDataAvailFlagsUasIdAvailable
→ const UtmDataAvailFlags
-
The field uas_id contains valid data.
-
utmDataAvailFlagsVerticalVeloAvailable
→ const UtmDataAvailFlags
-
The field vz contains valid data.
-
utmFlightStateAirborne
→ const UtmFlightState
-
UAS airborne.
-
utmFlightStateEmergency
→ const UtmFlightState
-
UAS is in an emergency flight state.
-
utmFlightStateGround
→ const UtmFlightState
-
UAS on ground.
-
utmFlightStateNoctrl
→ const UtmFlightState
-
UAS has no active controls.
-
utmFlightStateUnknown
→ const UtmFlightState
-
The flight state can't be determined.
-
videoStreamStatusFlagsRunning
→ const VideoStreamStatusFlags
-
Stream is active (running)
-
videoStreamStatusFlagsThermal
→ const VideoStreamStatusFlags
-
Stream is thermal imaging
-
videoStreamTypeMpegTsH264
→ const VideoStreamType
-
Stream is h.264 on MPEG TS (URI gives the port number)
-
videoStreamTypeRtpudp
→ const VideoStreamType
-
Stream is RTP UDP (URI gives the port number)
-
videoStreamTypeRtsp
→ const VideoStreamType
-
Stream is RTSP
-
videoStreamTypeTcpMpeg
→ const VideoStreamType
-
Stream is MPEG on TCP
-
vtolTransitionHeadingAny
→ const VtolTransitionHeading
-
Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active).
-
vtolTransitionHeadingNextWaypoint
→ const VtolTransitionHeading
-
Use the heading pointing towards the next waypoint.
-
vtolTransitionHeadingSpecified
→ const VtolTransitionHeading
-
Use the specified heading in parameter 4.
-
vtolTransitionHeadingTakeoff
→ const VtolTransitionHeading
-
Use the heading on takeoff (while sitting on the ground).
-
vtolTransitionHeadingVehicleDefault
→ const VtolTransitionHeading
-
Respect the heading configuration of the vehicle.
-
wifiConfigApModeAp
→ const WifiConfigApMode
-
WiFi configured as an access point.
-
wifiConfigApModeDisabled
→ const WifiConfigApMode
-
WiFi disabled.
-
wifiConfigApModeStation
→ const WifiConfigApMode
-
WiFi configured as a station connected to an existing local WiFi network.
-
wifiConfigApModeUndefined
→ const WifiConfigApMode
-
WiFi mode is undefined.
-
wifiConfigApResponseAccepted
→ const WifiConfigApResponse
-
Changes accepted.
-
wifiConfigApResponseModeError
→ const WifiConfigApResponse
-
Invalid Mode.
-
wifiConfigApResponsePasswordError
→ const WifiConfigApResponse
-
Invalid Password.
-
wifiConfigApResponseRejected
→ const WifiConfigApResponse
-
Changes rejected.
-
wifiConfigApResponseSsidError
→ const WifiConfigApResponse
-
Invalid SSID.
-
wifiConfigApResponseUndefined
→ const WifiConfigApResponse
-
Undefined response. Likely an indicative of a system that doesn't support this request.
-
winchAbandonLine
→ const WinchActions
-
Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored.
-
winchDeliver
→ const WinchActions
-
Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored.
-
winchHold
→ const WinchActions
-
Engage motor and hold current position. Only action and instance command parameters are used, others are ignored.
-
winchLoadLine
→ const WinchActions
-
Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored.
-
winchLoadPayload
→ const WinchActions
-
Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored
-
winchLock
→ const WinchActions
-
Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored.
-
winchRateControl
→ const WinchActions
-
Wind or unwind line at specified rate.
-
winchRelativeLengthControl
→ const WinchActions
-
Wind or unwind specified length of line, optionally using specified rate.
-
winchRelaxed
→ const WinchActions
-
Allow motor to freewheel.
-
winchRetract
→ const WinchActions
-
Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored.
-
zoomTypeContinuous
→ const CameraZoomType
-
Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming)
-
zoomTypeFocalLength
→ const CameraZoomType
-
Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)
-
zoomTypeHorizontalFov
→ const CameraZoomType
-
Zoom value as horizontal field of view in degrees.
-
zoomTypeRange
→ const CameraZoomType
-
Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)
-
zoomTypeStep
→ const CameraZoomType
-
Zoom one step increment (-1 for wide, 1 for tele)
Typedefs
-
ActuatorConfiguration
= int
-
Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.
-
ActuatorOutputFunction
= int
-
Actuator output function. Values greater or equal to 1000 are autopilot-specific.
-
AdsbAltitudeType
= int
-
Enumeration of the ADSB altimeter types
-
AdsbEmitterType
= int
-
ADSB classification for the type of vehicle emitting the transponder signal
-
AdsbFlags
= int
-
These flags indicate status such as data validity of each data source. Set = data valid
-
AisFlags
= int
-
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.
-
AisNavStatus
= int
-
Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html
-
AisType
= int
-
Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html
-
AttitudeTargetTypemask
= int
-
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.
-
AutotuneAxis
= int
-
Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.
-
CameraCapFlags
= int
-
Camera capability flags (Bitmap)
-
CameraMode
= int
-
Camera Modes.
-
CameraTrackingMode
= int
-
Camera tracking modes
-
CameraTrackingStatusFlags
= int
-
Camera tracking status flags
-
CameraTrackingTargetData
= int
-
Camera tracking target data (shows where tracked target is within image)
-
CameraZoomType
= int
-
Zoom types for MAV_CMD_SET_CAMERA_ZOOM
-
CanFilterOp
= int
-
CAN_FILTER_OP
-
CellularConfigResponse
= int
-
Possible responses from a CELLULAR_CONFIG message.
-
CellularNetworkFailedReason
= int
-
These flags are used to diagnose the failure state of CELLULAR_STATUS
-
CellularNetworkRadioType
= int
-
Cellular network radio type
-
CellularStatusFlag
= int
-
These flags encode the cellular network status
-
CompMetadataType
= int
-
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.
-
EscConnectionType
= int
-
Indicates the ESC connection type.
-
EscFailureFlags
= int
-
Flags to report ESC failures.
-
EstimatorStatusFlags
= int
-
Flags in ESTIMATOR_STATUS message
-
FailureType
= int
-
List of possible failure type to inject.
-
FailureUnit
= int
-
List of possible units where failures can be injected.
-
FenceAction
= int
-
Actions following geofence breach.
-
FenceBreach
= int
-
FENCE_BREACH
-
FenceMitigate
= int
-
Actions being taken to mitigate/prevent fence breach
-
FirmwareVersionType
= int
-
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.
-
GimbalDeviceCapFlags
= int
-
Gimbal device (low level) capability flags (bitmap).
-
GimbalDeviceErrorFlags
= int
-
Gimbal device (low level) error flags (bitmap, 0 means no error)
-
GimbalDeviceFlags
= int
-
Flags for gimbal device (lower level) operation.
-
GimbalManagerCapFlags
= int
-
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.
-
GimbalManagerFlags
= int
-
Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.
-
GpsFixType
= int
-
Type of GPS fix
-
GpsInputIgnoreFlags
= int
-
GPS_INPUT_IGNORE_FLAGS
-
GripperActions
= int
-
Gripper actions.
-
HighresImuUpdatedFlags
= int
-
Flags in the HIGHRES_IMU message indicate which fields have updated since the last message
-
HilSensorUpdatedFlags
= int
-
Flags in the HIL_SENSOR message indicate which fields have updated since the last message
-
HlFailureFlag
= int
-
Flags to report failure cases over the high latency telemetry.
-
LandingTargetType
= int
-
Type of landing target
-
MagCalStatus
= int
-
MAG_CAL_STATUS
-
MavArmAuthDeniedReason
= int
-
MAV_ARM_AUTH_DENIED_REASON
-
MavAutopilot
= int
-
Micro air vehicle / autopilot classes. This identifies the individual model.
-
MavBatteryChargeState
= int
-
Enumeration for battery charge states.
-
MavBatteryFault
= int
-
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.
-
MavBatteryFunction
= int
-
Enumeration of battery functions
-
MavBatteryMode
= int
-
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.
-
MavBatteryType
= int
-
Enumeration of battery types
-
MavCmd
= int
-
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
-
MavCollisionAction
= int
-
Possible actions an aircraft can take to avoid a collision.
-
MavCollisionSrc
= int
-
Source of information about this collision.
-
MavCollisionThreatLevel
= int
-
Aircraft-rated danger from this threat.
-
MavComponent
= int
-
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.
-
MavDataStream
= int
-
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.
-
MavDistanceSensor
= int
-
Enumeration of distance sensor types
-
MavDoRepositionFlags
= int
-
Bitmap of options for the MAV_CMD_DO_REPOSITION
-
MavEstimatorType
= int
-
Enumeration of estimator types
-
MavEventCurrentSequenceFlags
= int
-
Flags for CURRENT_EVENT_SEQUENCE.
-
MavEventErrorReason
= int
-
Reason for an event error response.
-
MavFrame
= int
-
Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles.
-
MavFtpErr
= int
-
MAV FTP error codes (https://mavlink.io/en/services/ftp.html)
-
MavFtpOpcode
= int
-
MAV FTP opcodes: https://mavlink.io/en/services/ftp.html
-
MavGeneratorStatusFlag
= int
-
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).
-
MavGoto
= int
-
Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.
-
MavLandedState
= int
-
Enumeration of landed detector states
-
MavlinkDataStreamType
= int
-
MAVLINK_DATA_STREAM_TYPE
-
MavMissionResult
= int
-
Result of mission operation (in a MISSION_ACK message).
-
MavMissionType
= int
-
Type of mission items being requested/sent in mission protocol.
-
MavMode
= int
-
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.
-
MavModeFlag
= int
-
These flags encode the MAV mode.
-
MavModeFlagDecodePosition
= int
-
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.
-
MavMountMode
= int
-
Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.
-
MavOdidArmStatus
= int
-
MAV_ODID_ARM_STATUS
-
MavOdidAuthType
= int
-
MAV_ODID_AUTH_TYPE
-
MavOdidCategoryEu
= int
-
MAV_ODID_CATEGORY_EU
-
MavOdidClassEu
= int
-
MAV_ODID_CLASS_EU
-
MavOdidClassificationType
= int
-
MAV_ODID_CLASSIFICATION_TYPE
-
MavOdidDescType
= int
-
MAV_ODID_DESC_TYPE
-
MavOdidHeightRef
= int
-
MAV_ODID_HEIGHT_REF
-
MavOdidHorAcc
= int
-
MAV_ODID_HOR_ACC
-
MavOdidIdType
= int
-
MAV_ODID_ID_TYPE
-
MavOdidOperatorIdType
= int
-
MAV_ODID_OPERATOR_ID_TYPE
-
MavOdidOperatorLocationType
= int
-
MAV_ODID_OPERATOR_LOCATION_TYPE
-
MavOdidSpeedAcc
= int
-
MAV_ODID_SPEED_ACC
-
MavOdidStatus
= int
-
MAV_ODID_STATUS
-
MavOdidTimeAcc
= int
-
MAV_ODID_TIME_ACC
-
MavOdidUaType
= int
-
MAV_ODID_UA_TYPE
-
MavOdidVerAcc
= int
-
MAV_ODID_VER_ACC
-
MavParamExtType
= int
-
Specifies the datatype of a MAVLink extended parameter.
-
MavParamType
= int
-
Specifies the datatype of a MAVLink parameter.
-
MavPowerStatus
= int
-
Power supply status flags (bitmask)
-
MavPreflightStorageAction
= int
-
Action required when performing CMD_PREFLIGHT_STORAGE
-
MavProtocolCapability
= int
-
Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.
-
MavResult
= int
-
Result from a MAVLink command (MAV_CMD)
-
MavRoi
= int
-
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).
-
MavSensorOrientation
= int
-
Enumeration of sensor orientation, according to its rotations
-
MavSeverity
= int
-
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/.
-
MavState
= int
-
MAV_STATE
-
MavSysStatusSensor
= int
-
These encode the sensors whose status is sent as part of the SYS_STATUS message.
-
MavSysStatusSensorExtended
= int
-
These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields.
-
MavTunnelPayloadType
= int
-
MAV_TUNNEL_PAYLOAD_TYPE
-
MavType
= int
-
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).
-
MavVtolState
= int
-
Enumeration of VTOL states
-
MavWinchStatusFlag
= int
-
Winch status flags used in WINCH_STATUS
-
MissionState
= int
-
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.
-
MotorTestOrder
= int
-
Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST.
-
MotorTestThrottleType
= int
-
Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST.
-
NavVtolLandOptions
= int
-
NAV_VTOL_LAND_OPTIONS
-
OrbitYawBehaviour
= int
-
Yaw behaviour during orbit flight.
-
ParachuteAction
= int
-
Parachute actions. Trigger release and enable/disable auto-release.
-
ParamAck
= int
-
Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).
-
PositionTargetTypemask
= int
-
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.
-
PrecisionLandMode
= int
-
Precision land modes (used in MAV_CMD_NAV_LAND).
-
PreflightStorageMissionAction
= int
-
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.)
-
PreflightStorageParameterAction
= int
-
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.)
-
RcType
= int
-
RC type
-
RtkBaselineCoordinateSystem
= int
-
RTK GPS baseline coordinate system, used for RTK corrections
-
SafetySwitchState
= int
-
Possible safety switch states.
-
SerialControlDev
= int
-
SERIAL_CONTROL device types
-
SerialControlFlag
= int
-
SERIAL_CONTROL flags (bitmask)
-
SetFocusType
= int
-
Focus types for MAV_CMD_SET_CAMERA_FOCUS
-
SpeedType
= int
-
Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED
-
StorageStatus
= int
-
Flags to indicate the status of camera storage.
-
StorageType
= int
-
Flags to indicate the type of storage.
-
StorageUsageFlag
= int
-
Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).
-
TuneFormat
= int
-
Tune formats (used for vehicle buzzer/tone generation).
-
UavcanNodeHealth
= int
-
Generalized UAVCAN node health
-
UavcanNodeMode
= int
-
Generalized UAVCAN node mode
-
UtmDataAvailFlags
= int
-
Flags for the global position report.
-
UtmFlightState
= int
-
Airborne status of UAS.
-
VideoStreamStatusFlags
= int
-
Stream status flags (Bitmap)
-
VideoStreamType
= int
-
Video stream types
-
VtolTransitionHeading
= int
-
Direction of VTOL transition
-
WifiConfigApMode
= int
-
WiFi Mode.
-
WifiConfigApResponse
= int
-
Possible responses from a WIFI_CONFIG_AP message.
-
WinchActions
= int
-
Winch actions.