mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 06:58:27 -04:00
AP_NavEKF3: move definition of MAX_EKF_CORES
if you're not including the AP_NavEKF3 header then you don't get this definition and then you won't be able to compile the DAL.
This commit is contained in:
parent
cef48fc432
commit
a794688f3b
@ -8,6 +8,7 @@
|
||||
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
|
||||
#include <AP_NavEKF/AP_Nav_Common.h>
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
|
@ -19,6 +19,8 @@
|
||||
#include <stdint.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#define MAX_EKF_CORES 3 // maximum allowed EKF Cores to be instantiated
|
||||
|
||||
// enumeration corresponding to buts within nav_filter_status union.
|
||||
// Only used for documentation purposes.
|
||||
enum class NavFilterStatusBit {
|
||||
|
@ -530,7 +530,6 @@ private:
|
||||
float core_delta; // the amount of D position change between cores when a change happened
|
||||
} pos_down_reset_data;
|
||||
|
||||
#define MAX_EKF_CORES 3 // maximum allowed EKF Cores to be instantiated
|
||||
#define CORE_ERR_LIM 1 // -LIM to LIM relative error range for a core
|
||||
#define BETTER_THRESH 0.5 // a lane should have this much relative error difference to be considered for overriding a healthy primary core
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user