AP_Hott_Telem: convert to new get_rpm() API

This commit is contained in:
Andrew Tridgell 2020-03-06 10:50:51 +11:00
parent 429c21b887
commit 0f83da7e16

View File

@ -147,8 +147,9 @@ void AP_Hott_Telem::send_EAM(void)
msg.climbrate3s = 120 + vel.z * -3; msg.climbrate3s = 120 + vel.z * -3;
const AP_RPM *rpm = AP::rpm(); const AP_RPM *rpm = AP::rpm();
if (rpm && rpm->enabled(0)) { float rpm_value;
msg.rpm = rpm->get_rpm(0) / 10; if (rpm && rpm->get_rpm(0, rpm_value)) {
msg.rpm = rpm_value * 0.1;
} }
AP_Stats *stats = AP::stats(); AP_Stats *stats = AP::stats();