AP_Hott_Telem: add and use AP_RPM_ENABLED

This commit is contained in:
Peter Barker 2022-08-12 09:35:06 +10:00 committed by Andrew Tridgell
parent e596f7ce83
commit bcf03eb01d
1 changed files with 2 additions and 0 deletions

View File

@ -148,11 +148,13 @@ void AP_Hott_Telem::send_EAM(void)
msg.climbrate = uint16_t(30000.5 + vel.z * -100);
msg.climbrate3s = 120 + vel.z * -3;
#if AP_RPM_ENABLED
const AP_RPM *rpm = AP::rpm();
float rpm_value;
if (rpm && rpm->get_rpm(0, rpm_value)) {
msg.rpm = rpm_value * 0.1;
}
#endif
AP_Stats *stats = AP::stats();
if (stats) {