Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 18 additions & 0 deletions message_definitions/v1.0/development.xml
Original file line number Diff line number Diff line change
Expand Up @@ -218,6 +218,24 @@
Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>
</message>
<message id="421" name="RC_CHANNELS_OVERRIDE_V2">
<wip since="2026-03"/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>
Highly bandwidth-efficient RC override message for professional networked operations (LTE, Zigbee, GCP).
Supersedes RC_CHANNELS_OVERRIDE by adding 32-channel support and a bitmask for multi-master conflict avoidance.
Uses centered-at-zero values and extension-field placement to maximize MAVLink 2 trailing-zero truncation.
</description>
<field type="uint8_t" name="target_system">System ID.</field>
<field type="uint8_t" name="target_component">Component ID.</field>
<field type="uint32_t" name="active_mask">Bitmap of included channels (bit 0 = CH1). 1: Valid/Override, 0: Ignore.</field>
<extensions/>
<field type="int16_t[32]" name="channels" minValue="-4096" maxValue="4096">
RC channels in centered 13-bit format. Range: -4096 to 4096, Center: 0.
Conversion to PWM: (x * 5/32) + 1500.
Unused channels must be set to 0 to enable MAVLink 2 trailing-zero trimming.
</field>
</message>
<message id="435" name="AVAILABLE_MODES">
<description>Get information about a particular flight modes.
The message can be enumerated or requested for a particular mode using MAV_CMD_REQUEST_MESSAGE.
Expand Down
Loading