From 4f54d9b75f3629c96dd3042f0708592644a0ffba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Mar 2020 10:50:52 +1100 Subject: [PATCH] AP_WindVane: convert to new get_rpm() API --- libraries/AP_WindVane/AP_WindVane_RPM.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane_RPM.cpp b/libraries/AP_WindVane/AP_WindVane_RPM.cpp index 311d645dee..75c44ad036 100644 --- a/libraries/AP_WindVane/AP_WindVane_RPM.cpp +++ b/libraries/AP_WindVane/AP_WindVane_RPM.cpp @@ -25,8 +25,9 @@ void AP_WindVane_RPM::update_speed() { const AP_RPM* rpm = AP_RPM::get_singleton(); if (rpm != nullptr) { - const float temp_speed = rpm->get_rpm(0); - if (!is_negative(temp_speed)) { + float temp_speed; + if (rpm->get_rpm(0, temp_speed) && + !is_negative(temp_speed)) { speed_update_frontend(temp_speed); } }