Skip to content

AP_RCProtocol: initialize parser state and tighten bounds#32816

Draft
vlordier wants to merge 1 commit intoArduPilot:masterfrom
vlordier:pr/ap-rcprotocol-init-and-parser-guards
Draft

AP_RCProtocol: initialize parser state and tighten bounds#32816
vlordier wants to merge 1 commit intoArduPilot:masterfrom
vlordier:pr/ap-rcprotocol-init-and-parser-guards

Conversation

@vlordier
Copy link
Copy Markdown

@vlordier vlordier commented Apr 18, 2026

This draft isolates the AP_RCProtocol and adjacent SUMD parser changes from the larger security-hardening branch.

Summary:

  • initialize parser/backend state that previously relied on default storage contents
  • tighten bounds handling in adjacent protocol parsing paths
  • add focused regression coverage for SUMD short-packet bounds handling and channel-order preservation

Why:

  • this keeps the review surface inside the RC protocol stack instead of mixing it with unrelated math, MAVLink, tooling, and documentation changes
  • the underlying changes are easier to reason about as protocol/parser correctness work than as a broad security PR

Validation:

  • branch was split cleanly from upstream/master
  • local configure succeeded in an isolated worktree
  • the branch now includes focused regression test coverage for the short-packet SUMD cases in this slice
  • full target execution was not completed in the worktree because the local worktree environment was missing submodule/build inputs needed for normal target enumeration

This PR is intentionally draft while the scope and test shape are reviewed.

Comment on lines +296 to +316
uint16_t _disabled_for_pulses{0};
bool _detected_with_bytes{false};
AP_RCProtocol_Backend *backend[NONE] = {};
bool _new_input{false};
uint32_t _last_input_ms{0};
bool _failsafe_active{false};
bool _valid_serial_prot{false};

// optional additional uart
struct {
AP_HAL::UARTDriver *uart;
bool opened;
uint32_t last_config_change_ms;
uint8_t config_num;
AP_HAL::UARTDriver *uart{nullptr};
bool opened{false};
uint32_t last_config_change_ms{0};
uint8_t config_num{0};
} added;

// allowed RC protocols mask (first bit means "all")
uint32_t rc_protocols_mask;
uint32_t rc_protocols_mask{0};

rcprotocol_t _last_detected_protocol;
bool _last_detected_using_uart;
rcprotocol_t _last_detected_protocol{NONE};
bool _last_detected_using_uart{false};
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not needed.

Comment on lines +137 to +142
uint32_t rc_input_count{0};
uint32_t last_rc_input_count{0};
uint32_t rc_frame_count{0};

uint16_t _pwm_values[MAX_RCIN_CHANNELS];
uint8_t _num_channels;
uint16_t _pwm_values[MAX_RCIN_CHANNELS] = {};
uint8_t _num_channels{0};
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no.

Comment on lines 209 to 242
@@ -227,25 +227,25 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend {
void start_uart();
AP_HAL::UARTDriver* get_current_UART() { return (_uart ? _uart : get_available_UART()); }

uint16_t _channels[CRSF_MAX_CHANNELS]; /* buffer for extracted RC channel data as pulsewidth in microseconds */
uint16_t _channels[CRSF_MAX_CHANNELS] = {}; /* buffer for extracted RC channel data as pulsewidth in microseconds */

uint32_t _last_frame_time_us;
uint32_t _last_tx_frame_time_us;
uint32_t _last_uart_start_time_ms;
uint32_t _last_rx_frame_time_us;
uint32_t _start_frame_time_us;
bool telem_available;
uint32_t _new_baud_rate;
bool _crsf_v3_active;
uint32_t _last_frame_time_us{0};
uint32_t _last_tx_frame_time_us{0};
uint32_t _last_uart_start_time_ms{0};
uint32_t _last_rx_frame_time_us{0};
uint32_t _start_frame_time_us{0};
bool telem_available{false};
uint32_t _new_baud_rate{0};
bool _crsf_v3_active{false};

bool _use_lq_for_rssi;
bool _use_lq_for_rssi{false};
int16_t derive_scaled_lq_value(uint8_t uplink_lq);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no

static const uint16_t RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES];

AP_HAL::UARTDriver *_uart;
AP_HAL::UARTDriver *_uart{nullptr};
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no.

Comment on lines 49 to 73
@@ -60,25 +60,25 @@ class AP_RCProtocol_DSM : public AP_RCProtocol_Backend {
BIND_STATE2,
BIND_STATE3,
BIND_STATE4,
} bind_state;
uint32_t bind_last_ms;
uint32_t bind_mode_saved;
} bind_state{BIND_STATE_NONE};
uint32_t bind_last_ms{0};
uint32_t bind_mode_saved{0};

uint16_t last_values[AP_DSM_MAX_CHANNELS];
uint16_t last_values[AP_DSM_MAX_CHANNELS] = {};

struct {
uint8_t buf[16];
uint8_t ofs;
uint8_t ofs{0};
} byte_input;

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no

Comment on lines +77 to +81
} dsm_decode_state{DSM_DECODE_STATE_DESYNC};

uint32_t last_frame_time_ms;
uint32_t last_rx_time_ms;
uint16_t chan_count;
uint32_t last_frame_time_ms{0};
uint32_t last_rx_time_ms{0};
uint16_t chan_count{0};
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no.

Comment on lines +56 to +59
uint8_t _rxlen{0};
ReceiverFcPacketHoTT _rxpacket;
uint16_t _crc16;
uint32_t last_packet_us;
uint16_t _crc16{0};
uint32_t last_packet_us{0};
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants