mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_RCProtocol: fixed a overflow in SRXL decoder
thanks to coverity 343308 and Peter for noticing
This commit is contained in:
parent
626c632859
commit
0f4c54aaa6
@ -18,7 +18,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
|
|
||||||
#define MAX_RCIN_CHANNELS 32
|
#define MAX_RCIN_CHANNELS 18
|
||||||
#define MIN_RCIN_CHANNELS 5
|
#define MIN_RCIN_CHANNELS 5
|
||||||
|
|
||||||
class AP_RCProtocol_Backend;
|
class AP_RCProtocol_Backend;
|
||||||
|
@ -22,6 +22,7 @@
|
|||||||
|
|
||||||
#include "AP_RCProtocol_SRXL.h"
|
#include "AP_RCProtocol_SRXL.h"
|
||||||
#include <AP_Math/crc.h>
|
#include <AP_Math/crc.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
// #define SUMD_DEBUG
|
// #define SUMD_DEBUG
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -233,20 +234,21 @@ void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||||||
crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
|
crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
|
||||||
if (crc_receiver == crc_fmu) {
|
if (crc_receiver == crc_fmu) {
|
||||||
/* at this point buffer contains all frame data and crc is valid --> extract channel info according to SRXL variant */
|
/* at this point buffer contains all frame data and crc is valid --> extract channel info according to SRXL variant */
|
||||||
uint16_t values[SRXL_MAX_CHANNELS];
|
const uint8_t max_values = MIN((unsigned)SRXL_MAX_CHANNELS,(unsigned)MAX_RCIN_CHANNELS);
|
||||||
|
uint16_t values[max_values];
|
||||||
uint8_t num_values;
|
uint8_t num_values;
|
||||||
bool failsafe_state;
|
bool failsafe_state;
|
||||||
switch (frame_header) {
|
switch (frame_header) {
|
||||||
case SRXL_HEADER_V1:
|
case SRXL_HEADER_V1:
|
||||||
srxl_channels_get_v1v2(MAX_RCIN_CHANNELS, &num_values, values, &failsafe_state);
|
srxl_channels_get_v1v2(max_values, &num_values, values, &failsafe_state);
|
||||||
add_input(num_values, values, failsafe_state);
|
add_input(num_values, values, failsafe_state);
|
||||||
break;
|
break;
|
||||||
case SRXL_HEADER_V2:
|
case SRXL_HEADER_V2:
|
||||||
srxl_channels_get_v1v2(MAX_RCIN_CHANNELS, &num_values, values, &failsafe_state);
|
srxl_channels_get_v1v2(max_values, &num_values, values, &failsafe_state);
|
||||||
add_input(num_values, values, failsafe_state);
|
add_input(num_values, values, failsafe_state);
|
||||||
break;
|
break;
|
||||||
case SRXL_HEADER_V5:
|
case SRXL_HEADER_V5:
|
||||||
srxl_channels_get_v5(MAX_RCIN_CHANNELS, &num_values, values, &failsafe_state);
|
srxl_channels_get_v5(max_values, &num_values, values, &failsafe_state);
|
||||||
add_input(num_values, values, failsafe_state);
|
add_input(num_values, values, failsafe_state);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user