AP_NavEKF: added #defines for VRBRAIN board
This commit is contained in:
parent
39d9e93904
commit
25f1c5774f
@ -311,7 +311,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
|
||||
prevStaticMode(true), // staticMode from previous filter update
|
||||
yawAligned(false) // set true when heading or yaw angle has been aligned
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
,_perf_UpdateFilter(perf_alloc(PC_ELAPSED, "EKF_UpdateFilter")),
|
||||
_perf_CovariancePrediction(perf_alloc(PC_ELAPSED, "EKF_CovariancePrediction")),
|
||||
_perf_FuseVelPosNED(perf_alloc(PC_ELAPSED, "EKF_FuseVelPosNED")),
|
||||
|
@ -32,7 +32,7 @@
|
||||
|
||||
#include <vectorN.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#include <systemlib/perf_counter.h>
|
||||
#endif
|
||||
|
||||
@ -458,7 +458,7 @@ private:
|
||||
} mag_state;
|
||||
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// performance counters
|
||||
perf_counter_t _perf_UpdateFilter;
|
||||
perf_counter_t _perf_CovariancePrediction;
|
||||
|
Loading…
Reference in New Issue
Block a user