mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_WindVane: convert to new get_rpm() API
This commit is contained in:
parent
ed37ebede8
commit
4f54d9b75f
@ -25,8 +25,9 @@ void AP_WindVane_RPM::update_speed()
|
|||||||
{
|
{
|
||||||
const AP_RPM* rpm = AP_RPM::get_singleton();
|
const AP_RPM* rpm = AP_RPM::get_singleton();
|
||||||
if (rpm != nullptr) {
|
if (rpm != nullptr) {
|
||||||
const float temp_speed = rpm->get_rpm(0);
|
float temp_speed;
|
||||||
if (!is_negative(temp_speed)) {
|
if (rpm->get_rpm(0, temp_speed) &&
|
||||||
|
!is_negative(temp_speed)) {
|
||||||
speed_update_frontend(temp_speed);
|
speed_update_frontend(temp_speed);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user