SET_MODE
Summary
The SET_MODE message is a legacy mechanism for changing the vehicle's flight mode (e.g., STABILIZE to GUIDED). While technically deprecated in favor of MAV_CMD_DO_SET_MODE (via COMMAND_LONG), ArduPilot maintains robust support for this message to ensure backward compatibility with older Ground Control Stations (GCS) and companion computers.
Directionality
- TX (Transmit): None (Vehicle modes are reported via
HEARTBEAT) - RX (Receive): All Vehicles (Triggers flight mode change)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_set_mode in libraries/GCS_MAVLink/GCS_Common.cpp.
Behaviors
- Flag Check: The handler first checks if
base_modehas theMAV_MODE_FLAG_CUSTOM_MODE_ENABLEDbit set. - Mode Extraction: If the flag is set, it extracts the
custom_modefield. This integer corresponds to ArduPilot's internal mode enums (e.g.,Copter::Mode::Number). - Execution: It calls
AP::vehicle()->set_mode(), attempting to transition the vehicle. - Feedback: Unlike command messages,
SET_MODEdoes not send an ACK. The GCS must monitor thecustom_modefield in subsequentHEARTBEATmessages to verify the transition was successful.
Data Fields
target_system: The system setting the mode.base_mode: The new base mode (MAV_MODE).custom_mode: The new autopilot-specific mode (MAV_MODE_FLAG_CUSTOM_MODE_ENABLEDmust be set).
Practical Use Cases
- Legacy Companion Computer Scripts:
- Scenario: An old Python script uses
master.set_mode_apm(4)(pymavlink) to switch a Copter to GUIDED mode. - Action: ArduPilot receives
SET_MODEwithcustom_mode=4and switches to GUIDED.
- Scenario: An old Python script uses
- Simple Mode Switching:
- Scenario: A minimal GCS implementation wants to land the drone without constructing complex
COMMAND_LONGpackets. - Action: Send
SET_MODEwithcustom_mode=9(Copter LAND).
- Scenario: A minimal GCS implementation wants to land the drone without constructing complex
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Contains
handle_set_modeand_set_mode_common. - ArduCopter/mode.h: Defines the mapping for
custom_modevalues for Copter.
RC_CHANNELS_SCALED
Summary
The scaled values of the RC channels.
Status
Supported (TX Only)
Directionality
- TX (Transmit): Rover (and possibly others) - Sends scaled servo/motor outputs.
- RX (Receive): None
Transmission (TX)
ArduRover sends this message to report the status of its motor outputs and control surfaces, scaled to -10000 to +10000.
Protocol Logic
- Scaling: -100% (-10000), 0% (0), +100% (10000).
- Fields: Channels 1-8. Inactive channels set to UINT16_MAX.
Data Fields
time_boot_ms: Timestamp.port: Servo output port (0 for primary).chan1_scaled: Channel 1 scaled value.chan2_scaled: Channel 2 scaled value.chan3_scaled: Channel 3 scaled value.chan4_scaled: Channel 4 scaled value.chan5_scaled: Channel 5 scaled value.chan6_scaled: Channel 6 scaled value.chan7_scaled: Channel 7 scaled value.chan8_scaled: Channel 8 scaled value.rssi: Received Signal Strength Indicator (0-255).
Practical Use Cases
- Rover Diagnostics:
- Scenario: Debugging skid-steering mixing.
- Action: GCS displays
chan1_scaled(Left Throttle) andchan3_scaled(Right Throttle) to verify the mixing logic.
Key Codebase Locations
- Rover/GCS_Mavlink.cpp:133: Sending implementation.
RC_CHANNELS_RAW
Summary
The RC_CHANNELS_RAW message provides raw PWM values (in microseconds) for the first 8 channels of the vehicle's radio receiver. While fully supported for backward compatibility, it is largely considered a legacy message in ArduPilot, having been superseded by RC_CHANNELS (65) which supports up to 18 channels.
Status
Legacy / Supported (Superseded by ID 65)
Directionality
- TX (Transmit): All Vehicles (Reports RC input to GCS/OSD)
- RX (Receive): None (Use
RC_CHANNELS_OVERRIDEfor GCS-based RC input)
Transmission (TX)
The transmission logic is in GCS_MAVLINK::send_rc_channels_raw within libraries/GCS_MAVLink/GCS_Common.cpp:2117.
Data Sourcing
- RC System: Data is retrieved via
rc().get_radio_in(values, 8). - Format: Raw PWM values (e.g., 1100 to 1900) for channels 1 through 8.
- RSSI: The message includes a
rssifield (0-255), representing the signal strength of the RC link.
Constraints
- Channel Limit: This message is strictly limited to 8 channels.
- MAVLink Versioning: ArduPilot primarily uses this message for MAVLink 1.0 compatibility. On modern MAVLink 2.0 links,
RC_CHANNELS(65) is the preferred method for streaming all 16+ channels.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).port: Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = Main, 1 = Aux.chan1_raw: RC channel 1 value.chan2_raw: RC channel 2 value.chan3_raw: RC channel 3 value.chan4_raw: RC channel 4 value.chan5_raw: RC channel 5 value.chan6_raw: RC channel 6 value.chan7_raw: RC channel 7 value.chan8_raw: RC channel 8 value.rssi: Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
Practical Use Cases
- Radio Calibration:
- Scenario: A user is setting up a new transmitter and needs to define the "Min" and "Max" stick positions.
- Action: Mission Planner monitors
RC_CHANNELS_RAWwhile the user moves the sticks, recording the extreme PWM values for each channel.
- Legacy OSD Display:
- Scenario: A pilot is using an old "MinimOSD" that only supports MAVLink 1.0.
- Action: The OSD reads
RC_CHANNELS_RAWto show a stick-position overlay or RSSI indicator on the video feed.
- Link Health Monitoring:
- Scenario: A developer wants to verify that their ELRS or Crossfire receiver is talking to the flight controller correctly.
- Action: By checking for fluctuating PWM values in
RC_CHANNELS_RAWin the GCS "Status" tab, the developer can confirm the digital link is alive.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2117: Implementation of the send function.
- libraries/RC_Channel/RC_Channels.cpp: Source of raw PWM input data.
SERVO_OUTPUT_RAW
Summary
The SERVO_OUTPUT_RAW message provides the actual PWM values (in microseconds) being sent to the vehicle's actuators (motors and servos). This represents the output of the flight controller's mixer logic and is crucial for verifying that the autopilot is commanding the hardware as expected.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports actuator state to GCS)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is implemented in GCS_MAVLINK::send_servo_output_raw within libraries/GCS_MAVLink/GCS_Common.cpp:3292.
Data Sourcing
- Hardware Read: PWM values are read directly from the hardware abstraction layer via
hal.rcout->read(). - Filtering: ArduPilot uses
SRV_Channels::get_output_channel_mask(SRV_Channel::k_GPIO)to identify and exclude any pins currently configured as GPIOs, ensuring only actuator signals are reported. - Extended Channel Support: While a single MAVLink
SERVO_OUTPUT_RAWpacket supports 16 channels, ArduPilot supports up to 32 outputs. It handles this by sending two packets:- Port 0: Channels 1-16.
- Port 1: Channels 17-32.
Scheduling
- Sent as part of the
MSG_SERVO_OUTPUT_RAWstream. - Triggered in
GCS_Common.cpp:6245within thetry_send_messageloop.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).port: Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = Main, 1 = Aux.servo1_raw: Servo output 1 value.servo2_raw: Servo output 2 value.servo3_raw: Servo output 3 value.servo4_raw: Servo output 4 value.servo5_raw: Servo output 5 value.servo6_raw: Servo output 6 value.servo7_raw: Servo output 7 value.servo8_raw: Servo output 8 value.servo9_raw: Servo output 9 value.servo10_raw: Servo output 10 value.servo11_raw: Servo output 11 value.servo12_raw: Servo output 12 value.servo13_raw: Servo output 13 value.servo14_raw: Servo output 14 value.servo15_raw: Servo output 15 value.servo16_raw: Servo output 16 value.
Practical Use Cases
- Mixer Verification:
- Scenario: A builder has configured a complex V-Tail plane and wants to ensure the tail servos move correctly in response to elevator and rudder inputs.
- Action: The builder observes
SERVO_OUTPUT_RAWin the GCS while moving the sticks to verify the mixer output without propellers attached.
- Motor Saturation Check:
- Scenario: A heavy-lift Octocopter is struggling to maintain altitude.
- Action: The pilot checks the
servo_rawvalues. If multiple motors are consistently at2000(Max PWM), it indicates the vehicle is underpowered or overloaded.
- Actuator Health Monitoring:
- Scenario: A servo starts drawing excessive current or becomes jittery.
- Action: Mission Planner graphs the output values. If the output is steady but the vehicle is unstable, it points to a mechanical failure in the actuator itself.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3292: Implementation of
send_servo_output_raw. - libraries/GCS_MAVLink/GCS_Common.cpp:6245: Scheduler logic.
SET_GPS_GLOBAL_ORIGIN
Summary
Sets the GPS coordinates of the vehicle's local origin (0,0,0).
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives EKF origin data.
Reception (RX)
Handled by GCS_MAVLink::handle_set_gps_global_origin.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Used to manually set the EKF origin. This is crucial for non-GPS navigation (e.g., Optical Flow, Vicon) where the vehicle needs a global reference frame to align with the real world or to "fake" a GPS lock at a specific location.
- Sets:
AP::[ahrs](/field-manual/mavlink-interface/ahrs.html)().set_origin().
Data Fields
target_system: System ID.latitude: Latitude (deg * 1E7).longitude: Longitude (deg * 1E7).altitude: Altitude (mm).time_usec: Timestamp.
Practical Use Cases
- Indoor-Outdoor Transition:
- Scenario: A drone takes off indoors (Vicon) and flies outdoors (GPS).
- Action: The GCS or companion computer sets the global origin to the building's entrance coordinates so the indoor local coordinates map correctly to global lat/lon.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:4192: Handler.
NAV_CONTROLLER_OUTPUT
Summary
The NAV_CONTROLLER_OUTPUT message provides the output of the vehicle's navigation controllers and its progress toward the current waypoint. It is a critical telemetry packet for the Ground Control Station's (GCS) HUD, as it provides "Desired" versus "Actual" navigation data, often visualized as a "Flight Director" or heading bug.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports navigation state)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is vehicle-specific, as each vehicle type (Plane, Copter, Rover) has unique navigation requirements.
ArduPlane Logic
Implemented in ArduPlane/GCS_Mavlink.cpp:201.
nav_roll/nav_pitch: Sourced from the plane's internal navigation target angles (nav_roll_cd,nav_pitch_cd).wp_dist: Calculated distance to the active waypoint in meters.alt_error: Vertical distance from the target altitude in meters.aspd_error: Difference between target airspeed and current filtered airspeed (multiplied by 100).
ArduCopter Logic
Implemented in ArduCopter/GCS_Mavlink.cpp:206.
nav_bearing: The bearing required to reach the next waypoint.target_bearing: The heading the vehicle is currently trying to maintain.xtrack_error: The cross-track error (perpendicular distance from the path) in meters.
Data Fields
nav_roll: Current desired roll in degrees.nav_pitch: Current desired pitch in degrees.nav_bearing: Current desired heading in degrees.target_bearing: Bearing to current waypoint/target in degrees.wp_dist: Distance to active waypoint in meters.alt_error: Current altitude error in meters.aspd_error: Current airspeed error in meters/second.xtrack_error: Current crosstrack error on x-y plane in meters.
Practical Use Cases
- Flight Director HUD:
- Navigation Health Monitoring:
- Scenario: A drone is fighting high crosswinds.
- Action: The pilot monitors
xtrack_error. If the error keeps increasing despite the drone leaning into the wind, it indicates the wind speed exceeds the drone's tilt limits.
- Approach Visualization:
- Scenario: A Rover is following a path through a series of narrow gates.
- Action: The GCS uses
wp_distto show a countdown timer or distance bar to the next gate, helping the operator anticipate turns.
Key Codebase Locations
- ArduPlane/GCS_Mavlink.cpp:201: Plane-specific navigation output.
- ArduCopter/GCS_Mavlink.cpp:206: Copter-specific navigation output.
- Rover/GCS_Mavlink.cpp:103: Rover-specific navigation output.
RC_CHANNELS
Summary
The RC_CHANNELS message is the modern standard for streaming the vehicle's radio control input to a Ground Control Station (GCS). It supports up to 18 channels of data, providing high-resolution PWM values and a link quality indicator (RSSI). This message is used by GCS software for radio calibration and real-time stick visualization.
Status
Supported / Recommended
Directionality
- TX (Transmit): All Vehicles (Reports RC input to GCS/OSD)
- RX (Receive): None (Use
RC_CHANNELS_OVERRIDEorRADIO_RC_CHANNELSfor input)
Transmission (TX)
The transmission logic is in GCS_MAVLINK::send_rc_channels within libraries/GCS_MAVLink/GCS_Common.cpp:2081.
Data Sourcing
- RC System: Values are retrieved from the
RC_Channelssingleton usingget_radio_in(). - Channel Count: While the MAVLink message supports 18 channels, ArduPilot typically supports up to 16 channels (
NUM_RC_CHANNELS), which are mapped to the first 16 fields of the message. - RSSI: Sourced from the receiver driver (e.g., CRSF, ELRS, SBUS) and mapped to the $0$-$255$ range.
- Timestamp: Uses
AP_HAL::millis()since boot.
Stream Configuration
- Sent as part of the
MSG_RC_CHANNELSstream. - This message is active on modern MAVLink 2.0 links and is the preferred way to monitor full-range radio inputs (e.g., auxiliary switches, camera dials).
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).chancount: Total number of RC channels being received.chan1_raw: RC channel 1 value.chan2_raw: RC channel 2 value.chan3_raw: RC channel 3 value.chan4_raw: RC channel 4 value.chan5_raw: RC channel 5 value.chan6_raw: RC channel 6 value.chan7_raw: RC channel 7 value.chan8_raw: RC channel 8 value.chan9_raw: RC channel 9 value.chan10_raw: RC channel 10 value.chan11_raw: RC channel 11 value.chan12_raw: RC channel 12 value.chan13_raw: RC channel 13 value.chan14_raw: RC channel 14 value.chan15_raw: RC channel 15 value.chan16_raw: RC channel 16 value.chan17_raw: RC channel 17 value.chan18_raw: RC channel 18 value.rssi: Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
Practical Use Cases
- Full System Calibration:
- Scenario: A user is configuring a complex cinema drone with 12 auxiliary switches for camera tilt, zoom, and mode selection.
- Action: Mission Planner uses
RC_CHANNELSto show the movement of all 12 channels simultaneously in the "Mandatory Hardware" setup screen.
- Telemetry-based Stick Display:
- Scenario: A pilot wants to record their stick movements for a YouTube tutorial.
- Action: An OSD or GCS records the
RC_CHANNELSstream, allowing the pilot to overlay a "Stick Cam" on the final video using only telemetry logs.
- Radio Link Health (RSSI):
- Scenario: A pilot is flying a long-distance mission.
- Action: The GCS HUD displays the
rssifield as a percentage. If the value drops significantly, the pilot knows they are approaching the limit of their radio range.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2081: Implementation of the send function.
- libraries/RC_Channel/RC_Channel.h:14: Defines
NUM_RC_CHANNELS.
REQUEST_DATA_STREAM
Summary
Request a data stream (e.g., "All", "Raw Sensors", "RC Channels").
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives stream requests.
Description
This message is Deprecated in favor of MAV_CMD_SET_MESSAGE_INTERVAL but remains widely supported for legacy GCS compatibility.
Reception (RX)
Handled by GCS_MAVLINK::handle_request_data_stream.
Source: libraries/GCS_MAVLink/GCS_Param.cpp
Protocol Logic
The GCS requests a "Stream ID" (e.g., MAV_DATA_STREAM_EXTENDED_STATUS) and a rate (Hz). ArduPilot maps this ID to a set of actual MAVLink messages and sets their transmission interval.
Data Fields
target_system: System ID.target_component: Component ID.req_stream_id: ID of requested stream (0=All).req_message_rate: Rate in Hz.start_stop: 1 to start, 0 to stop.
Practical Use Cases
- Connecting GCS:
- Scenario: Mission Planner connects.
- Action: It sends
REQUEST_DATA_STREAMfor "ALL" streams at defined rates to start the telemetry flow.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Param.cpp:129: Handler.
MANUAL_CONTROL
Summary
Raw manual control inputs (Joystick) from the GCS.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives joystick input.
Reception (RX)
Handled by GCS_MAVLINK::handle_manual_control.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Used for "Joystick" or "Virtual RC" control where the GCS sends control axes directly, rather than the RC receiver.
- Mapping: The X/Y/Z/R axes are mapped to Roll/Pitch/Throttle/Yaw (or similar) based on vehicle type and mode.
- Buttons: Button bits are decoded to trigger auxiliary functions (like arming, mode switching).
Data Fields
target: Target system.x: X-axis (Pitch) -1000..1000.y: Y-axis (Roll) -1000..1000.z: Z-axis (Throttle) 0..1000.r: R-axis (Yaw) -1000..1000.buttons: 16-bit button mask.buttons2: Extension for more buttons.
Practical Use Cases
- Flying via Tablet:
- Scenario: User flies a drone using on-screen virtual joysticks in QGroundControl.
- Action: QGC sends
MANUAL_CONTROLmessages. ArduPilot treats these as pilot input, overriding (or replacing) the physical RC receiver.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:7038: Handler.
RC_CHANNELS_OVERRIDE
Summary
The RC_CHANNELS_OVERRIDE message allows a Ground Control Station (GCS) to emulate a physical radio transmitter. By sending this message, a GCS can take direct control of the vehicle's sticks and switches, bypassing the physical RC receiver. This is the primary mechanism for flying drones using USB Joysticks, Gamepads, or automated ground-based control logic.
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Enables GCS control)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_rc_channels_override in libraries/GCS_MAVLink/GCS_Common.cpp:3994.
Application Logic
- Security: ArduPilot only accepts overrides from the System ID configured as "My GCS" (
SYSID_MYGCS). - Channel Handling:
- Value 1000-2000: Sets the raw PWM value for that channel.
- Value 0 or 65535 (
UINT16_MAX): "Ignore". The current override for this channel is maintained, or it remains on physical RC. - Value 65534: "Release". Forces this specific channel to revert to the physical radio input.
- Persistence: Overrides are applied to the
RC_Channelslibrary and remain active until a timeout occurs or they are explicitly released.
Timeout and Failsafe
ArduPilot implements a safety watchdog for overrides in RC_Channel::has_override() (libraries/RC_Channel/RC_Channel.cpp:510).
- Heartbeat: If no new
RC_CHANNELS_OVERRIDEmessage is received within the time defined by theRC_OVERRIDE_TIMEparameter (default 3 seconds), the autopilot automatically releases all overrides. - Failsafe: If no physical RC receiver is present and the GCS override times out, the vehicle triggers an RC Failsafe (typically RTL or Land).
Data Fields
target_system: System ID.target_component: Component ID.chan1_raw: RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan2_raw: RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan3_raw: RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan4_raw: RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan5_raw: RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan6_raw: RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan7_raw: RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan8_raw: RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan9_raw: RC channel 9 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan10_raw: RC channel 10 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan11_raw: RC channel 11 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan12_raw: RC channel 12 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan13_raw: RC channel 13 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan14_raw: RC channel 14 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan15_raw: RC channel 15 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan16_raw: RC channel 16 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan17_raw: RC channel 17 value, in microseconds. A value of UINT16_MAX means to ignore this field.chan18_raw: RC channel 18 value, in microseconds. A value of UINT16_MAX means to ignore this field.
Practical Use Cases
- Joystick Flying:
- Scenario: A pilot wants to fly a drone using an Xbox controller connected to their laptop.
- Action: Mission Planner reads the controller inputs and streams
RC_CHANNELS_OVERRIDEmessages at 10Hz-25Hz to the drone.
- GCS-Triggered Actions:
- Scenario: A search-and-rescue team uses a button on their GCS dashboard to "Drop Payload".
- Action: The GCS sends a single
RC_CHANNELS_OVERRIDEpacket for Channel 8 with a value of2000to trigger the gripper.
- Automated Landing Logic:
- Scenario: An external vision system is performing a precision landing on a moving platform.
- Action: The vision system sends micro-adjustments to the roll/pitch channels via overrides to center the drone over the target.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3994: Entry point for override handling.
- libraries/RC_Channel/RC_Channel.cpp:510: Implementation of the timeout/failsafe logic.
- libraries/RC_Channel/RC_Channel.h: Defines the override state storage.
COMMAND_INT
Summary
Send a command with up to seven parameters to the MAV. This is the preferred method for sending commands that involve location data (Latitude/Longitude), as it uses integers for precision.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives commands.
Reception (RX)
Handled by GCS_MAVLINK::handle_command_int.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
- Decoding: Extracts the command ID (
MAV_CMD) and parameters. - Routing: Dispatches to the appropriate handler (e.g.,
handle_MAV_CMD_DO_SET_ROI). - Frame: Explicitly handles the
framefield (e.g.,MAV_FRAME_GLOBAL_RELATIVE_ALT), whichCOMMAND_LONGlacks.
Data Fields
target_system: System ID.target_component: Component ID.frame: Coordinate frame (MAV_FRAME).command: Command ID (MAV_CMD).current: (Not used).autocontinue: (Not used).param1: Parameter 1 (float).param2: Parameter 2 (float).param3: Parameter 3 (float).param4: Parameter 4 (float).x: Latitude/X (int32).y: Longitude/Y (int32).z: Altitude/Z (float).
Practical Use Cases
- Region of Interest (ROI):
- Scenario: User points the camera at a specific GPS coordinate.
- Action: GCS sends
COMMAND_INT(CMD:MAV_CMD_DO_SET_ROI) with the lat/lon inx/y.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5643: Handler.
COMMAND_LONG
Summary
The COMMAND_LONG message is the most versatile and critical control packet in the MAVLink protocol. It is used to trigger one-off actions or transition the vehicle into complex states. Commands range from basic operations like Arming and Disarming to advanced functions like initiating a Compass Calibration or triggering a camera shutter. ArduPilot processes these by mapping the message to an internal MAV_CMD dispatch system.
Status
Supported (Critical)
Directionality
- TX (Transmit): All Vehicles (Used to control external components like Gimbals/Cameras)
- RX (Receive): All Vehicles (Main entry point for GCS-initiated actions)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_command_long in libraries/GCS_MAVLink/GCS_Common.cpp:5176.
Execution Flow
- Scripting Override: If a Lua script has registered for a specific command (e.g., a custom payload trigger), ArduPilot's C++ handler yields to the script.
- Unification: ArduPilot converts
COMMAND_LONG(float params) into an internalCOMMAND_INT(integer params) format viatry_command_long_as_command_int(GCS_Common.cpp:5125) to ensure consistent processing across both message types. - Dispatch: The command is routed to
handle_command_int_packet. Vehicle-specific logic (e.g., ArduCopter/GCS_Mavlink.cpp:758) first attempts to handle vehicle-specific commands (likeTAKEOFForLAND). If unhandled, it falls back to the common handler inGCS_MAVLINK. - Acknowledgement: Every
COMMAND_LONGmust be acknowledged. ArduPilot sends aCOMMAND_ACK(77) back to the GCS with the result of the operation.
Transmission (TX)
ArduPilot acts as a controller for peripheral devices using COMMAND_LONG.
- Gimbal Control: ArduPilot sends
MAV_CMD_DO_MOUNT_CONTROLto move a MAVLink-enabled gimbal. - Camera Integration: It sends
MAV_CMD_DO_DIGICAM_CONTROLto trigger photo capture on external MAVLink cameras.
Data Fields
target_system: System which should execute the command.target_component: Component which should execute the command, 0 for all components.command: Command ID (MAV_CMD).confirmation: 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command).param1: Parameter 1 (for the specific command).param2: Parameter 2 (for the specific command).param3: Parameter 3 (for the specific command).param4: Parameter 4 (for the specific command).param5: Parameter 5 (for the specific command).param6: Parameter 6 (for the specific command).param7: Parameter 7 (for the specific command).
Practical Use Cases
- Arming the Vehicle:
- Scenario: A pilot is ready for takeoff and clicks "Arm" in the GCS.
- Action: The GCS sends
COMMAND_LONGwithcommand = MAV_CMD_COMPONENT_ARM_DISARM (400)andparam1 = 1. ArduPilot verifies safety checks and arms the motors.
- Triggering a Reboot:
- Scenario: A user has updated a critical parameter that requires a power cycle.
- Action: The GCS sends
COMMAND_LONGwithcommand = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246). ArduPilot saves logs and restarts the MCU.
- Emergency Return-to-Launch:
- Scenario: The pilot loses orientation and needs the drone to come back.
- Action: Clicking the "RTL" button sends
COMMAND_LONGwithcommand = MAV_CMD_NAV_RETURN_TO_LAUNCH (20).
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5176: Main command entry point.
- libraries/GCS_MAVLink/GCS_Common.cpp:5415: Common
MAV_CMDdispatch switch. - ArduCopter/GCS_Mavlink.cpp:758: Copter-specific command overrides.
COMMAND_ACK
Summary
The COMMAND_ACK message is the response to a COMMAND_LONG or COMMAND_INT. It informs the sender whether the requested command was accepted, denied, or if it failed during execution. For long-running tasks, it can also provide progress updates. This message is critical for any Ground Control Station to provide reliable feedback to the user after they click a button or send a command.
Status
Supported (Critical)
Directionality
- TX (Transmit): All Vehicles (Confirming results to GCS)
- RX (Receive): Specific Subsystems (Receiving ACKs from external components like Gimbals)
Transmission (TX)
Transmission happens automatically after a command is processed by GCS_MAVLINK::handle_command_long or handle_command_int.
Result Types
ArduPilot uses the following standard MAV_RESULT values:
MAV_RESULT_ACCEPTED(0): Command was valid and has been executed (or started).MAV_RESULT_TEMPORARILY_REJECTED(1): Command is valid but cannot be executed now (e.g., trying to Arm while the vehicle is already armed).MAV_RESULT_DENIED(2): Command is invalid or the vehicle is in a state that prohibits it (e.g., Takeoff while disarmed).MAV_RESULT_UNSUPPORTED(3): The requestedMAV_CMDis not implemented in ArduPilot.MAV_RESULT_FAILED(4): The command was accepted but failed to complete (e.g., a motor failed to spin up during an arming attempt).MAV_RESULT_IN_PROGRESS(5): The command is being processed. ArduPilot may send subsequent ACKs with aprogressvalue (0-100%).
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_command_ack in libraries/GCS_MAVLink/GCS_Common.cpp:3978.
Usage
ArduPilot listens for ACKs when it acts as a controller for other MAVLink devices.
- Accel Calibration: Used in libraries/AP_AccelCal/AP_AccelCal.cpp to verify that external sensors have acknowledged calibration steps.
- Gimbal Control: ArduPilot verifies that an external MAVLink gimbal has accepted its orientation commands.
Data Fields
command: Command ID (MAV_CMD).result: Result code (MAV_RESULT).progress: Progress (0 to 100, or 255 if not supported).result_param2: Additional parameter for result (optional).target_system: System ID of the target.target_component: Component ID of the target.
Practical Use Cases
- GCS UI Feedback:
- Scenario: A user clicks "Arm".
- Action: The GCS displays "Arming..." and waits for the
COMMAND_ACK. If it receivesACCEPTED, the UI turns Red (Armed). If it receivesTEMPORARILY_REJECTED, the GCS shows a popup: "Pre-arm checks failed".
- Automated Scripts:
- Scenario: A Python script is performing an automated test of the camera trigger.
- Action: The script sends
MAV_CMD_DO_DIGICAM_CONTROLand blocks until it receives aCOMMAND_ACK. This ensures the script doesn't proceed faster than the hardware can respond.
- Calibration Progress:
- Scenario: A user is performing a Compass Calibration.
- Action: ArduPilot sends
COMMAND_ACKwithMAV_RESULT_IN_PROGRESSand theprogressfield updated (e.g., 10%, 20%...) as the user rotates the vehicle.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3978: Reception handler.
- libraries/GCS_MAVLink/GCS_Common.cpp:5200: Typical location where
mavlink_msg_command_ack_sendis called after a command is processed. - libraries/AP_AccelCal/AP_AccelCal.cpp: Example of RX handling.
MANUAL_SETPOINT
Summary
Manual setpoint message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
Theoretical Use Cases
Manual control setpoints.
SET_ATTITUDE_TARGET
Summary
Sets the vehicle's attitude (roll, pitch, yaw) and throttle target. Primary method for offboard control in "Guided" mode.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives offboard control targets.
Reception (RX)
Handled by GCS_MAVLINK::handle_set_attitude_target.
Source: ArduCopter/GCS_Mavlink.cpp
Protocol Logic
- Bitmask: The
type_maskfield determines which fields are ignored. ArduPilot supports various combinations (e.g., Attitude only, Rates only, or mixed). - Input: Quaternions for attitude, rad/s for rates, 0..1 for thrust.
- Mode: Requires vehicle to be in
GUIDED(Copter) or similar offboard mode.
Data Fields
time_boot_ms: Timestamp.target_system: System ID.target_component: Component ID.type_mask: Bitmap to ignore fields.q: Attitude quaternion (w, x, y, z).body_roll_rate: Roll rate (rad/s).body_pitch_rate: Pitch rate (rad/s).body_yaw_rate: Yaw rate (rad/s).thrust: Collective thrust (0.0 to 1.0).
Practical Use Cases
- Companion Computer Control:
- Scenario: An onboard NVIDIA Jetson is flying the drone using a neural network.
- Action: The Jetson sends
SET_ATTITUDE_TARGETat 50Hz to control the drone's orientation and thrust directly.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:1205: Handler.
ATTITUDE_TARGET
Summary
The ATTITUDE_TARGET message provides the "Desired" orientation of the vehicle, as commanded by the flight controller's navigation and position loops. By comparing this message against the actual orientation (reported in ATTITUDE or ATTITUDE_QUATERNION), Ground Control Stations can visualize how well the vehicle is tracking its commanded path and tuning parameters.
Status
Supported
Directionality
- TX (Transmit): Copter, Plane (QuadPlane only), Blimp (Reports desired targets)
- RX (Receive): None (Use
SET_ATTITUDE_TARGET(82) for external input)
Transmission (TX)
The transmission logic is implemented in vehicle-specific GCS classes.
Copter Implementation
Located in ArduCopter/GCS_Mavlink.cpp:86.
- Data Source: The
AC_AttitudeControllibrary provides the internal targets. - Format:
q: The target orientation as a unit quaternion.body_roll_rate,body_pitch_rate,body_yaw_rate: The target angular velocities in rad/s.thrust: The normalized target thrust (0 to 1).
Plane Implementation
Located in ArduPlane/GCS_Mavlink.cpp:160.
- This message is typically only sent when the plane is in a VTOL (Vertical Take-Off and Landing) mode (QuadPlane), where the attitude controller's targets are relevant for hover stability.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).type_mask: Bitmap to indicate which dimensions should be ignored by the vehicle.q: Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0).body_roll_rate: Body roll rate (rad/s).body_pitch_rate: Body pitch rate (rad/s).body_yaw_rate: Body yaw rate (rad/s).thrust: Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust).
Practical Use Cases
- PID Tuning Visualization:
- Scenario: A user is performing manual "AutoTune" and wants to see if the drone is responsive enough.
- Action: The GCS graphs "Actual Roll" vs. "Target Roll" (from
ATTITUDE_TARGET). If the actual roll lags significantly behind the target, the user knows to increase the P-gain.
- Navigation Health Monitoring:
- Scenario: A drone is flying in extremely high winds.
- Action: The pilot notices the "Desired Tilt" (Target) is at 30 degrees, but the drone is only tilting 20 degrees. This indicates a physical limitation or motor saturation.
- Simulation Verification:
- Scenario: A developer is testing a new navigation algorithm in SITL.
- Action: By logging
ATTITUDE_TARGET, the developer can verify that the algorithm is generating smooth, mathematically sound setpoints before they are passed to the motors.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:86: Copter transmission logic.
- ArduPlane/GCS_Mavlink.cpp:160: Plane transmission logic.
- libraries/AC_AttitudeControl/AC_AttitudeControl.h: Internal source of target orientation.
Summary
Sets the vehicle's position, velocity, and/or acceleration target in a local North-East-Down (NED) frame.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives local offboard control targets.
Reception (RX)
Handled by GCS_MAVLINK::handle_set_position_target_local_ned.
Source: ArduCopter/GCS_Mavlink.cpp
Protocol Logic
- Frame: Supports
MAV_FRAME_LOCAL_NED,MAV_FRAME_LOCAL_OFFSET_NED,MAV_FRAME_BODY_NED,MAV_FRAME_BODY_OFFSET_NED. - Mask:
type_maskignores unused fields. - Control: Can control Position (XYZ), Velocity (XYZ), Acceleration (XYZ), and Yaw/YawRate.
Data Fields
time_boot_ms: Timestamp.target_system: System ID.target_component: Component ID.coordinate_frame: Valid MAV_FRAME.type_mask: Ignore flags.x: X Position (m).y: Y Position (m).z: Z Position (m).vx: X Velocity (m/s).vy: Y Velocity (m/s).vz: Z Velocity (m/s).afx: X Acceleration (m/s^2).afy: Y Acceleration (m/s^2).afz: Z Acceleration (m/s^2).yaw: Yaw angle (rad).yaw_rate: Yaw rate (rad/s).
Practical Use Cases
- Vision-Based Following:
- Scenario: A drone tracks a person using a camera.
- Action: The onboard computer calculates the relative vector to the person and sends velocity commands (
vx,vy) viaSET_POSITION_TARGET_LOCAL_NED(Frame:MAV_FRAME_BODY_NED) to keep the person centered.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:1280: Handler.
POSITION_TARGET_LOCAL_NED
Summary
Reports the current commanded vehicle position, velocity, and acceleration in the local NED frame.
Status
Supported (TX Only)
Directionality
- TX (Transmit): Copter, Plane, Rover - Sends current target state.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report what the autopilot is trying to achieve (the setpoint), which might differ from the actual vehicle state (LOCAL_POSITION_NED).
Source: ArduCopter/GCS_Mavlink.cpp
Protocol Logic
Queries the active flight mode controller (e.g., pos_control) for its target position, velocity, and acceleration.
Data Fields
time_boot_ms: Timestamp.coordinate_frame: MAV_FRAME_LOCAL_NED.type_mask: Bitmap of valid fields.x: Target X (m).y: Target Y (m).z: Target Z (m).vx: Target VX (m/s).vy: Target VY (m/s).vz: Target VZ (m/s).afx: Target Accel X.afy: Target Accel Y.afz: Target Accel Z.yaw: Target Yaw.yaw_rate: Target Yaw Rate.
Practical Use Cases
- Control Loop Analysis:
- Scenario: Investigating "toilet bowling" (oscillation).
- Action: GCS plots
POSITION_TARGET_LOCAL_NED.xvsLOCAL_POSITION_NED.x. If the target leads the actual position correctly, the navigator is fine. If the target oscillates wildly, the navigation tuning is bad.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:142: Sending implementation.
Summary
Sets the vehicle's position, velocity, and/or acceleration target in the Global frame (Latitude/Longitude).
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives global offboard control targets.
Reception (RX)
Handled by GCS_MAVLINK::handle_set_position_target_global_int.
Source: ArduCopter/GCS_Mavlink.cpp
Protocol Logic
- Frame: Supports
MAV_FRAME_GLOBAL_INT,MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,MAV_FRAME_GLOBAL_TERRAIN_ALT_INT. - Precision: Uses integers (deg * 1E7) for Lat/Lon to prevent floating point errors.
Data Fields
time_boot_ms: Timestamp.target_system: System ID.target_component: Component ID.coordinate_frame: MAV_FRAME.type_mask: Ignore flags.lat_int: Latitude.lon_int: Longitude.alt: Altitude (m).vx: Velocity X.vy: Velocity Y.vz: Velocity Z.afx: Accel X.afy: Accel Y.afz: Accel Z.yaw: Yaw.yaw_rate: Yaw Rate.
Practical Use Cases
- Dynamic Re-tasking:
- Scenario: Search and Rescue drone.
- Action: Operator clicks a point on the map. The GCS sends a
SET_POSITION_TARGET_GLOBAL_INTto fly the drone to that specific coordinate in Guided mode.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:1386: Handler.
POSITION_TARGET_GLOBAL_INT
Summary
Reports the current commanded vehicle position, velocity, and acceleration in the Global frame.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends current target state.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the current navigation target in global coordinates.
Source: ArduCopter/GCS_Mavlink.cpp
Data Fields
time_boot_ms: Timestamp.coordinate_frame: MAV_FRAME.type_mask: Bitmap of valid fields.lat_int: Target Latitude.lon_int: Target Longitude.alt: Target Altitude (m).vx: Target VX.vy: Target VY.vz: Target VZ.afx: Target Accel X.afy: Target Accel Y.afz: Target Accel Z.yaw: Target Yaw.yaw_rate: Target Yaw Rate.
Practical Use Cases
- Target Visualization:
- Scenario: Autonomous mission.
- Action: GCS draws a "Ghost Drone" on the map representing the
POSITION_TARGET_GLOBAL_INT. This shows where the drone wants to be vs where it is.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:109: Sending implementation.
SET_ACTUATOR_CONTROL_TARGET
Summary
The SET_ACTUATOR_CONTROL_TARGET message is designed to set the "Actuator Control Target," which allows for direct control of the vehicle's actuators (motors and servos) normalized from -1.0 to 1.0. This bypasses the higher-level flight modes and rate controllers.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
For direct actuator control, ArduPilot typically uses:
RC_CHANNELS_OVERRIDE(70): To override radio inputs.MAV_CMD_DO_SET_SERVO: To set a specific servo to a PWM value.MAV_CMD_DO_SET_ACTUATOR: A newer command to control actuators.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).group_mlx: Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.target_system: System ID.target_component: Component ID.controls: Actuator controls. Normed -1..+1 where 0 is neutral or de-throttled. Each action system number 0 is also a special value and means no action. The mapping of controls to actuators is vehicle specific.
ACTUATOR_CONTROL_TARGET
Summary
The ACTUATOR_CONTROL_TARGET message reports the current "Target" state of the actuators (motors and servos), normalized from -1.0 to 1.0. This allows a Ground Control Station (GCS) to monitor what the mixer is trying to achieve.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
Instead, ArduPilot uses:
SERVO_OUTPUT_RAW(36): To report the actual PWM output sent to the motors.NAV_CONTROLLER_OUTPUT(62): To report high-level navigation targets (Roll, Pitch, Bearing).
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).group_mlx: Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.controls: Actuator controls. Normed -1..+1 where 0 is neutral or de-throttled. Each action system number 0 is also a special value and means no action. The mapping of controls to actuators is vehicle specific.
FOLLOW_TARGET
Summary
The FOLLOW_TARGET message reports the kinematic state (position, velocity, attitude) of a target vehicle or object that the drone should follow. This message is typically sent by a Ground Control Station (GCS) or a companion computer acting as a "virtual beacon."
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Updates Follow Me target)
Reception (RX)
Reception is handled by AP_Follow::handle_follow_target_message within libraries/AP_Follow/AP_Follow.cpp:374.
Protocol Logic
- Validation: The message is ignored if the Lat/Lon are zero or if the
est_capabilitiesbitmask doesn't indicate valid position data. - Target Update:
- Position: Lat, Lon, and Alt (AMSL) are updated.
- Velocity: If provided (
est_capabilitiesbit 1), the target's NED velocity is updated. - Heading: If attitude quaternion is provided (
est_capabilitiesbit 3), the target's heading is extracted.
- Timestamping: The
timestampfield is jitter-corrected to align the external time base with the autopilot's boot time.
Data Fields
timestamp: Timestamp (ms since boot).est_capabilities: Bitmask of valid fields (1: Pos, 2: Vel, 4: Accel, 8: Att).lat: Latitude (deg * 1E7).lon: Longitude (deg * 1E7).alt: Altitude (meters AMSL).vel: Velocity (m/s) in NED frame.acc: Acceleration (m/s^2).attitude_q: Attitude quaternion (w, x, y, z).rates: Angular rates (rad/s).position_cov: Position covariance.custom_state: Custom state field.
Practical Use Cases
- Computer Vision Tracking:
- Scenario: A companion computer tracks a car using a camera.
- Action: It estimates the car's GPS coordinates and velocity, then streams
FOLLOW_TARGETto the flight controller. The drone flies in "Follow" mode, smoothly tracking the car.
- Swarm Formation:
- Scenario: Drone B follows Drone A.
- Action: Drone A broadcasts its position (via
GLOBAL_POSITION_INTor similar). The GCS or an onboard script reformats this intoFOLLOW_TARGETand sends it to Drone B.
Key Codebase Locations
- libraries/AP_Follow/AP_Follow.cpp:374: Implementation of the handler.
SET_MAG_OFFSETS
Summary
The SET_MAG_OFFSETS message was historically used to set the magnetometer calibration offsets.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It is deprecated.
Modern systems use:
- Onboard Compass Calibration: Invoked via
MAV_CMD_DO_START_MAG_CAL(42424) orMAG_CAL_REPORTmessages. - Parameters: Setting
COMPASS_OFS_X/Y/Zdirectly.
Data Fields
target_system: System ID.target_component: Component ID.mag_ofs_x: Magnetometer X offset.mag_ofs_y: Magnetometer Y offset.mag_ofs_z: Magnetometer Z offset.
SET_HOME_POSITION
Summary
The SET_HOME_POSITION message is defined in the MAVLink standard to allow Ground Control Stations to update the vehicle's home location. However, ArduPilot does not implement a handler for this specific message ID. Instead, ArduPilot uses the command-based MAV_CMD_DO_SET_HOME (via COMMAND_LONG or COMMAND_INT) to manage home position updates.
Status
Unsupported (Use MAV_CMD_DO_SET_HOME instead)
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
ArduPilot prefers the command protocol (MAV_CMD) for state changes because it provides a standardized acknowledgement mechanism (COMMAND_ACK). Standalone messages like SET_HOME_POSITION often lack built-in ACKs, making them less reliable for critical safety operations.
- Alternative: Ground Control Stations should send a
COMMAND_LONGwithcommand = 179 (MAV_CMD_DO_SET_HOME). - Behavior: When received via the command protocol, ArduPilot verifies that the vehicle is disarmed (in most configurations) before committing the new home coordinates to the AHRS and storage.
Data Fields (Standard)
target_system: System ID.latitude: Latitude (WGS84), in degrees * 1E7.longitude: Longitude (WGS84, in degrees * 1E7.altitude: Altitude (MSL), in meters * 1000 (positive for up).x: Local X position of this position in the local coordinate frame.y: Local Y position of this position in the local coordinate frame.z: Local Z position of this position in the local coordinate frame.q: World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground.approach_x: Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.approach_y: Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.approach_z: Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5529: Handling of the
MAV_CMD_DO_SET_HOMEequivalent.
BUTTON_CHANGE
Summary
Report a change in the state of a physical button connected to the autopilot.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends button events.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when the AP_Button library detects a state change (press/release) on a configured button pin.
Source: libraries/AP_Button/AP_Button.cpp
Data Fields
time_boot_ms: Timestamp.last_change_ms: Time of last change.state: New state (0=Released, 1=Pressed).
Practical Use Cases
- Safety Switch Monitoring:
- Scenario: User presses the safety button on the GPS mast.
- Action: The GCS receives
BUTTON_CHANGE, confirming the action.
Key Codebase Locations
- libraries/AP_Button/AP_Button.cpp:355: Sending implementation.
ACTUATOR_OUTPUT_STATUS
Summary
The ACTUATOR_OUTPUT_STATUS message is designed to report the status of actuators (servos, motors) in a more flexible array format (up to 32 actuators) compared to the older SERVO_OUTPUT_RAW (limited to 16).
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot relies on SERVO_OUTPUT_RAW (36) to report the PWM output values of its servo channels (1-16). For higher channel counts or specific actuator feedback, other mechanisms or multiple messages would be required, but ACTUATOR_OUTPUT_STATUS is not currently used.
Intended Data Fields (Standard)
time_usec: Timestamp (us since UNIX epoch).active: Number of active actuators.actuator: Array of 32 float values (output).
Theoretical Use Cases
- Complex Robotics:
- Scenario: A hexapod robot with 18 servos (3 per leg).
- Action:
SERVO_OUTPUT_RAWcan only report the first 16.ACTUATOR_OUTPUT_STATUSallows reporting all 18 joint angles in a single atomic message frame, simplifying the log analysis for walking gaits.
- Normalized Feedback: