AP_NavEKF2: use common header for optimisation level and irq disable
This commit is contained in:
parent
a017ae7e00
commit
d1dfd5fd01
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
@ -150,11 +145,9 @@ void NavEKF2_core::SelectMagFusion()
|
||||
}
|
||||
// fuse the three magnetometer componenents sequentially
|
||||
for (mag_state.obsIndex = 0; mag_state.obsIndex <= 2; mag_state.obsIndex++) {
|
||||
irqstate_t istate = irqsave();
|
||||
perf_begin(_perf_test[0]);
|
||||
FuseMagnetometer();
|
||||
perf_end(_perf_test[0]);
|
||||
irqrestore(istate);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -3,12 +3,6 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
@ -351,6 +346,9 @@ void NavEKF2_core::UpdateFilter()
|
||||
}
|
||||
|
||||
// start the timer used for load measurement
|
||||
#if EK2_DISABLE_INTERRUPTS
|
||||
irqstate_t istate = irqsave();
|
||||
#endif
|
||||
perf_begin(_perf_UpdateFilter);
|
||||
|
||||
// TODO - in-flight restart method
|
||||
@ -404,6 +402,9 @@ void NavEKF2_core::UpdateFilter()
|
||||
|
||||
// stop the timer used for load measurement
|
||||
perf_end(_perf_UpdateFilter);
|
||||
#if EK2_DISABLE_INTERRUPTS
|
||||
irqrestore(istate);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -21,10 +21,14 @@
|
||||
#ifndef AP_NavEKF2_core
|
||||
#define AP_NavEKF2_core
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "AP_NavEKF2.h"
|
||||
#pragma GCC optimize("O3")
|
||||
|
||||
// #define MATH_CHECK_INDEXES 1
|
||||
// #define EK2_DISABLE_INTERRUPTS 1
|
||||
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "AP_NavEKF2.h"
|
||||
|
||||
#include <AP_Math/vectorN.h>
|
||||
|
||||
|
@ -4,11 +4,6 @@
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||
|
||||
/*
|
||||
optionally turn down optimisation for debugging
|
||||
*/
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
#include "AP_NavEKF2.h"
|
||||
#include "AP_NavEKF2_core.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
Loading…
Reference in New Issue
Block a user