mirror of https://github.com/ArduPilot/ardupilot
DataFlash: Fix allocating extra values for RC logging
This commit is contained in:
parent
c8cb5b9e0f
commit
6469a985d7
|
@ -198,8 +198,8 @@ void DataFlash_Class::Log_Write_RFND(const RangeFinder &rangefinder)
|
|||
// Write an RCIN packet
|
||||
void DataFlash_Class::Log_Write_RCIN(void)
|
||||
{
|
||||
uint16_t values[16] = {};
|
||||
rc().get_radio_in(values, 14);
|
||||
uint16_t values[14] = {};
|
||||
rc().get_radio_in(values, ARRAY_SIZE(values));
|
||||
struct log_RCIN pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RCIN_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
|
|
Loading…
Reference in New Issue