AP_NavEKF2: stop including AP_DAL.h in header

it's not needed and will slow compilation down
This commit is contained in:
Peter Barker 2024-08-30 18:35:16 +10:00 committed by Peter Barker
parent 2675e293ed
commit 2bb6846d47
6 changed files with 18 additions and 20 deletions

View File

@ -1,6 +1,7 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_NavEKF2_core.h" #include "AP_NavEKF2_core.h"
#include <AP_DAL/AP_DAL.h>
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h> #include <AP_Vehicle/AP_Vehicle_Type.h>

View File

@ -1,9 +1,8 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h" #include "AP_NavEKF2_core.h"
extern const AP_HAL::HAL& hal; #include <AP_DAL/AP_DAL.h>
#include "AP_NavEKF2.h"
/******************************************************** /********************************************************
* RESET FUNCTIONS * * RESET FUNCTIONS *

View File

@ -1,11 +1,9 @@
#include <AP_HAL/AP_HAL.h> #include "AP_NavEKF2_core.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_DAL/AP_DAL.h>
#include "AP_NavEKF2.h" #include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
// Control filter mode transitions // Control filter mode transitions
void NavEKF2_core::controlFilterModes() void NavEKF2_core::controlFilterModes()

View File

@ -1,9 +1,6 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_NavEKF2_core.h" #include "AP_NavEKF2_core.h"
extern const AP_HAL::HAL& hal; #include <AP_DAL/AP_DAL.h>
/* Monitor GPS data to see if quality is good enough to initialise the EKF /* Monitor GPS data to see if quality is good enough to initialise the EKF
Monitor magnetometer innovations to see if the heading is good enough to use GPS Monitor magnetometer innovations to see if the heading is good enough to use GPS

View File

@ -1,8 +1,10 @@
#include "AP_NavEKF2_core.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_DAL/AP_DAL.h>
#include <GCS_MAVLink/GCS.h>
#include "AP_NavEKF2.h" #include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;

View File

@ -29,7 +29,8 @@
#include <AP_Math/vectorN.h> #include <AP_Math/vectorN.h>
#include <AP_NavEKF/AP_NavEKF_core_common.h> #include <AP_NavEKF/AP_NavEKF_core_common.h>
#include <AP_NavEKF/EKF_Buffer.h> #include <AP_NavEKF/EKF_Buffer.h>
#include <AP_DAL/AP_DAL.h> #include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Beacon/AP_Beacon_config.h>
#include "AP_NavEKF/EKFGSF_yaw.h" #include "AP_NavEKF/EKFGSF_yaw.h"
@ -341,7 +342,7 @@ public:
private: private:
EKFGSF_yaw *yawEstimator; EKFGSF_yaw *yawEstimator;
AP_DAL &dal; class AP_DAL &dal;
// Reference to the global EKF frontend for parameters // Reference to the global EKF frontend for parameters
class NavEKF2 *frontend; class NavEKF2 *frontend;