mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Logger: log valid-input and in-rc-failsafe
Can now sensibly log these now the RC_Channels library has the methods
This commit is contained in:
parent
ffc553f34f
commit
86aad6f6bf
@ -431,6 +431,11 @@ private:
|
||||
BLOCK = (1<<2),
|
||||
};
|
||||
|
||||
enum class RCLoggingFlags : uint8_t {
|
||||
HAS_VALID_INPUT = 1U<<0, // true if the system is receiving good RC values
|
||||
IN_RC_FAILSAFE = 1U<<1, // true if the system is current in RC failsafe
|
||||
};
|
||||
|
||||
/*
|
||||
* support for dynamic Write; user-supplies name, format,
|
||||
* labels and values in a single function call.
|
||||
|
@ -159,28 +159,21 @@ void AP_Logger::Write_RCIN(void)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
const uint16_t override_mask = rc().get_override_mask();
|
||||
|
||||
// don't waste logging bandwidth if we haven't seen non-zero
|
||||
// channels 15/16:
|
||||
if (!should_log_rcin2) {
|
||||
if (values[14] || values[15]) {
|
||||
should_log_rcin2 = true;
|
||||
} else if (override_mask != 0) {
|
||||
should_log_rcin2 = true;
|
||||
}
|
||||
uint8_t flags = 0;
|
||||
if (rc().has_valid_input()) {
|
||||
flags |= (uint8_t)AP_Logger::RCLoggingFlags::HAS_VALID_INPUT;
|
||||
}
|
||||
if (rc().in_rc_failsafe()) {
|
||||
flags |= (uint8_t)AP_Logger::RCLoggingFlags::IN_RC_FAILSAFE;
|
||||
}
|
||||
|
||||
if (!should_log_rcin2) {
|
||||
return;
|
||||
}
|
||||
|
||||
const struct log_RCIN2 pkt2{
|
||||
LOG_PACKET_HEADER_INIT(LOG_RCIN2_MSG),
|
||||
const struct log_RCI2 pkt2{
|
||||
LOG_PACKET_HEADER_INIT(LOG_RCI2_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
chan15 : values[14],
|
||||
chan16 : values[15],
|
||||
override_mask : override_mask,
|
||||
override_mask : rc().get_override_mask(),
|
||||
flags : flags,
|
||||
};
|
||||
WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
|
@ -262,12 +262,13 @@ struct PACKED log_RCIN {
|
||||
uint16_t chan14;
|
||||
};
|
||||
|
||||
struct PACKED log_RCIN2 {
|
||||
struct PACKED log_RCI2 {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint16_t chan15;
|
||||
uint16_t chan16;
|
||||
uint16_t override_mask;
|
||||
uint8_t flags;
|
||||
};
|
||||
|
||||
struct PACKED log_RCOUT {
|
||||
@ -971,6 +972,8 @@ struct PACKED log_VER {
|
||||
// @Field: C15: channel 15 input
|
||||
// @Field: C16: channel 16 input
|
||||
// @Field: OMask: bitmask of RC channels being overridden by mavlink input
|
||||
// @Field: Flags: bitmask of RC state flags
|
||||
// @FieldBitmaskEnum: Flags: AP_Logger::RCLoggingFlags
|
||||
|
||||
// @LoggerMessage: RCIN
|
||||
// @Description: RC input channels to vehicle
|
||||
@ -1204,8 +1207,8 @@ LOG_STRUCTURE_FROM_GPS \
|
||||
"MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \
|
||||
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
||||
"RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \
|
||||
{ LOG_RCIN2_MSG, sizeof(log_RCIN2), \
|
||||
"RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---", true }, \
|
||||
{ LOG_RCI2_MSG, sizeof(log_RCI2), \
|
||||
"RCI2", "QHHHB", "TimeUS,C15,C16,OMask,Flags", "sYY--", "F----", true }, \
|
||||
{ LOG_RCOUT_MSG, sizeof(log_RCOUT), \
|
||||
"RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \
|
||||
{ LOG_RCOUT2_MSG, sizeof(log_RCOUT2), \
|
||||
@ -1324,7 +1327,7 @@ enum LogMessages : uint8_t {
|
||||
LOG_IDS_FROM_NAVEKF3,
|
||||
LOG_MESSAGE_MSG,
|
||||
LOG_RCIN_MSG,
|
||||
LOG_RCIN2_MSG,
|
||||
LOG_RCI2_MSG,
|
||||
LOG_RCOUT_MSG,
|
||||
LOG_RSSI_MSG,
|
||||
LOG_IDS_FROM_BARO,
|
||||
|
Loading…
Reference in New Issue
Block a user