AP_WindVane: add and use AP_RPM_ENABLED

... and backend-specific equivalents
This commit is contained in:
Peter Barker 2022-07-15 21:53:41 +10:00 committed by Andrew Tridgell
parent 4758fabe0d
commit 61a8d6311b
2 changed files with 4 additions and 2 deletions

View File

@ -15,8 +15,11 @@
#include "AP_WindVane_RPM.h"
#include <AP_RPM/AP_RPM.h>
void AP_WindVane_RPM::update_speed()
{
#if AP_RPM_ENABLED
const AP_RPM* rpm = AP_RPM::get_singleton();
if (rpm != nullptr) {
float temp_speed;
@ -25,4 +28,5 @@ void AP_WindVane_RPM::update_speed()
_frontend._speed_apparent_raw = temp_speed;
}
}
#endif // AP_RPM_ENABLED
}

View File

@ -16,8 +16,6 @@
#include "AP_WindVane_Backend.h"
#include <AP_RPM/AP_RPM.h>
class AP_WindVane_RPM : public AP_WindVane_Backend
{
public: