mirror of https://github.com/ArduPilot/ardupilot
DataFlash: support logging up to 14 RC input channels
This commit is contained in:
parent
6039eab442
commit
6bf2b5033e
|
@ -216,6 +216,12 @@ struct PACKED log_RCIN {
|
|||
uint16_t chan6;
|
||||
uint16_t chan7;
|
||||
uint16_t chan8;
|
||||
uint16_t chan9;
|
||||
uint16_t chan10;
|
||||
uint16_t chan11;
|
||||
uint16_t chan12;
|
||||
uint16_t chan13;
|
||||
uint16_t chan14;
|
||||
};
|
||||
|
||||
struct PACKED log_RCOUT {
|
||||
|
@ -364,7 +370,7 @@ struct PACKED log_Radio {
|
|||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||
"MSG", "Z", "Message"}, \
|
||||
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
||||
"RCIN", "Ihhhhhhhh", "TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8" }, \
|
||||
"RCIN", "Ihhhhhhhhhhhhhh", "TimeMS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14" }, \
|
||||
{ LOG_RCOUT_MSG, sizeof(log_RCOUT), \
|
||||
"RCOU", "Ihhhhhhhh", "TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8" }, \
|
||||
{ LOG_BARO_MSG, sizeof(log_BARO), \
|
||||
|
|
|
@ -709,9 +709,10 @@ void DataFlash_Class::Log_Write_GPS2(const GPS *gps)
|
|||
// Write an RCIN packet
|
||||
void DataFlash_Class::Log_Write_RCIN(void)
|
||||
{
|
||||
uint32_t timestamp = hal.scheduler->millis();
|
||||
struct log_RCIN pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RCIN_MSG),
|
||||
timestamp : hal.scheduler->millis(),
|
||||
timestamp : timestamp,
|
||||
chan1 : hal.rcin->read(0),
|
||||
chan2 : hal.rcin->read(1),
|
||||
chan3 : hal.rcin->read(2),
|
||||
|
@ -719,7 +720,13 @@ void DataFlash_Class::Log_Write_RCIN(void)
|
|||
chan5 : hal.rcin->read(4),
|
||||
chan6 : hal.rcin->read(5),
|
||||
chan7 : hal.rcin->read(6),
|
||||
chan8 : hal.rcin->read(7)
|
||||
chan8 : hal.rcin->read(7),
|
||||
chan9 : hal.rcin->read(8),
|
||||
chan10 : hal.rcin->read(9),
|
||||
chan11 : hal.rcin->read(10),
|
||||
chan12 : hal.rcin->read(11),
|
||||
chan13 : hal.rcin->read(12),
|
||||
chan14 : hal.rcin->read(13)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue