Browse Source

DataFlash: Fix allocating extra values for RC logging

master
Michael du Breuil 7 years ago committed by Andrew Tridgell
parent
commit
6469a985d7
  1. 4
      libraries/DataFlash/LogFile.cpp

4
libraries/DataFlash/LogFile.cpp

@ -198,8 +198,8 @@ void DataFlash_Class::Log_Write_RFND(const RangeFinder &rangefinder) @@ -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…
Cancel
Save