mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: correct SITL backend compilation if RPM disabled in SITL
This commit is contained in:
parent
e2fd4fc782
commit
855f4fe2d2
|
@ -13,14 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "RPM_SITL.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
#if AP_RPM_SIM_ENABLED
|
||||
|
||||
/*
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
/*
|
||||
open the sensor in constructor
|
||||
*/
|
||||
AP_RPM_SITL::AP_RPM_SITL(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
|
||||
|
@ -46,4 +45,4 @@ void AP_RPM_SITL::update(void)
|
|||
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // AP_RPM_SIM_ENABLED
|
||||
|
|
|
@ -14,9 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
#include "AP_RPM.h"
|
||||
|
||||
#if AP_RPM_SIM_ENABLED
|
||||
|
||||
#include "RPM_Backend.h"
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
|
@ -33,4 +34,4 @@ private:
|
|||
uint8_t instance;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // AP_RPM_SIM_ENABLED
|
||||
|
|
Loading…
Reference in New Issue