AP_RPM: Improve rpm logging

This commit is contained in:
MattKear 2024-06-14 17:56:14 +01:00 committed by Peter Barker
parent aafa2f3998
commit 2025712505
2 changed files with 26 additions and 19 deletions

View File

@ -214,9 +214,7 @@ void AP_RPM::update(void)
} }
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED
if (enabled(0) || enabled(1)) { Log_RPM();
Log_RPM();
}
#endif #endif
} }
@ -295,18 +293,23 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED
void AP_RPM::Log_RPM() const void AP_RPM::Log_RPM() const
{ {
float rpm1 = -1, rpm2 = -1; // update logging for each instance
for (uint8_t i=0; i<num_instances; i++) {
if (drivers[i] == nullptr || !enabled(i)) {
// don't log unused instances
continue;
}
get_rpm(0, rpm1); const struct log_RPM pkt{
get_rpm(1, rpm2); LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
time_us : AP_HAL::micros64(),
const struct log_RPM pkt{ inst : i,
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG), rpm : state[i].rate_rpm,
time_us : AP_HAL::micros64(), quality : get_signal_quality(i),
rpm1 : rpm1, health : uint8_t(healthy(i))
rpm2 : rpm2 };
}; AP::logger().WriteBlock(&pkt, sizeof(pkt));
AP::logger().WriteBlock(&pkt, sizeof(pkt)); }
} }
#endif #endif

View File

@ -8,15 +8,19 @@
// @LoggerMessage: RPM // @LoggerMessage: RPM
// @Description: Data from RPM sensors // @Description: Data from RPM sensors
// @Field: TimeUS: Time since system startup // @Field: TimeUS: Time since system startup
// @Field: rpm1: First sensor's data // @Field: I: Instance
// @Field: rpm2: Second sensor's data // @Field: RPM: Sensor's rpm measurement
// @Field: Qual: Signal quality
// @Field: H: Sensor Health (Bool)
struct PACKED log_RPM { struct PACKED log_RPM {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us; uint64_t time_us;
float rpm1; uint8_t inst;
float rpm2; float rpm;
float quality;
uint8_t health;
}; };
#define LOG_STRUCTURE_FROM_RPM \ #define LOG_STRUCTURE_FROM_RPM \
{ LOG_RPM_MSG, sizeof(log_RPM), \ { LOG_RPM_MSG, sizeof(log_RPM), \
"RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" , true }, "RPM", "QBffB", "TimeUS,I,RPM,Qual,H", "s#q--", "F-000" , true },