Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_RPM: Demystifying RPM sensors #27306

Merged
merged 1 commit into from
Jul 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 17 additions & 14 deletions libraries/AP_RPM/AP_RPM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,9 +214,7 @@ void AP_RPM::update(void)
}

#if HAL_LOGGING_ENABLED
if (enabled(0) || enabled(1)) {
Log_RPM();
}
Log_RPM();
#endif
}

Expand Down Expand Up @@ -295,18 +293,23 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const
#if HAL_LOGGING_ENABLED
void AP_RPM::Log_RPM() const
{
float rpm1 = -1, rpm2 = -1;

get_rpm(0, rpm1);
get_rpm(1, rpm2);
// 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;
}

const struct log_RPM pkt{
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
time_us : AP_HAL::micros64(),
rpm1 : rpm1,
rpm2 : rpm2
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
const struct log_RPM pkt{
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
time_us : AP_HAL::micros64(),
inst : i,
rpm : state[i].rate_rpm,
quality : get_signal_quality(i),
health : uint8_t(healthy(i))
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
}
#endif

Expand Down
14 changes: 9 additions & 5 deletions libraries/AP_RPM/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,19 @@
// @LoggerMessage: RPM
// @Description: Data from RPM sensors
// @Field: TimeUS: Time since system startup
// @Field: rpm1: First sensor's data
// @Field: rpm2: Second sensor's data
// @Field: I: Instance
// @Field: RPM: Sensor's rpm measurement
// @Field: Qual: Signal quality
// @Field: H: Sensor Health (Bool)
struct PACKED log_RPM {
LOG_PACKET_HEADER;
uint64_t time_us;
float rpm1;
float rpm2;
uint8_t inst;
float rpm;
float quality;
uint8_t health;
};

#define LOG_STRUCTURE_FROM_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 },
Loading