mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
4758fabe0d
commit
61a8d6311b
|
@ -15,8 +15,11 @@
|
||||||
|
|
||||||
#include "AP_WindVane_RPM.h"
|
#include "AP_WindVane_RPM.h"
|
||||||
|
|
||||||
|
#include <AP_RPM/AP_RPM.h>
|
||||||
|
|
||||||
void AP_WindVane_RPM::update_speed()
|
void AP_WindVane_RPM::update_speed()
|
||||||
{
|
{
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const AP_RPM* rpm = AP_RPM::get_singleton();
|
const AP_RPM* rpm = AP_RPM::get_singleton();
|
||||||
if (rpm != nullptr) {
|
if (rpm != nullptr) {
|
||||||
float temp_speed;
|
float temp_speed;
|
||||||
|
@ -25,4 +28,5 @@ void AP_WindVane_RPM::update_speed()
|
||||||
_frontend._speed_apparent_raw = temp_speed;
|
_frontend._speed_apparent_raw = temp_speed;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
}
|
}
|
||||||
|
|
|
@ -16,8 +16,6 @@
|
||||||
|
|
||||||
#include "AP_WindVane_Backend.h"
|
#include "AP_WindVane_Backend.h"
|
||||||
|
|
||||||
#include <AP_RPM/AP_RPM.h>
|
|
||||||
|
|
||||||
class AP_WindVane_RPM : public AP_WindVane_Backend
|
class AP_WindVane_RPM : public AP_WindVane_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
Loading…
Reference in New Issue