mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
DataFlash: log 14 output channels in RCOU
unfortunately this means we need to shorten the column headers, but at least this makes us consistent with RCIN
This commit is contained in:
parent
53df307c2d
commit
a06e46a84c
@ -803,7 +803,9 @@ void DataFlash_Class::Log_Write_RCOUT(void)
|
||||
chan9 : hal.rcout->read(8),
|
||||
chan10 : hal.rcout->read(9),
|
||||
chan11 : hal.rcout->read(10),
|
||||
chan12 : hal.rcout->read(11)
|
||||
chan12 : hal.rcout->read(11),
|
||||
chan13 : hal.rcout->read(12),
|
||||
chan14 : hal.rcout->read(13)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
Log_Write_ESC();
|
||||
|
@ -172,6 +172,8 @@ struct PACKED log_RCOUT {
|
||||
uint16_t chan10;
|
||||
uint16_t chan11;
|
||||
uint16_t chan12;
|
||||
uint16_t chan13;
|
||||
uint16_t chan14;
|
||||
};
|
||||
|
||||
struct PACKED log_RSSI {
|
||||
@ -730,7 +732,7 @@ Format characters in the format string for binary log messages
|
||||
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
||||
"RCIN", "Qhhhhhhhhhhhhhh", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14" }, \
|
||||
{ LOG_RCOUT_MSG, sizeof(log_RCOUT), \
|
||||
"RCOU", "Qhhhhhhhhhhhh", "TimeUS,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Ch8,Ch9,Ch10,Ch11,Ch12" }, \
|
||||
"RCOU", "Qhhhhhhhhhhhhhh", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14" }, \
|
||||
{ LOG_RSSI_MSG, sizeof(log_RSSI), \
|
||||
"RSSI", "Qf", "TimeUS,RXRSSI" }, \
|
||||
{ LOG_BARO_MSG, sizeof(log_BARO), \
|
||||
|
Loading…
Reference in New Issue
Block a user