Skip to content

Commit

Permalink
AP_NavEKF2: stop including AP_DAL.h in header
Browse files Browse the repository at this point in the history
it's not needed and will slow compilation down
  • Loading branch information
peterbarker committed Aug 30, 2024
1 parent 6d844d8 commit df20e35
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 19 deletions.
5 changes: 3 additions & 2 deletions libraries/AP_NavEKF2/AP_NavEKF2.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2_core.h"

#include <AP_DAL/AP_DAL.h>
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
Expand Down
7 changes: 3 additions & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"

extern const AP_HAL::HAL& hal;
#include <AP_DAL/AP_DAL.h>

#include "AP_NavEKF2.h"

/********************************************************
* RESET FUNCTIONS *
Expand Down
8 changes: 3 additions & 5 deletions libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;
#include <GCS_MAVLink/GCS.h>
#include <AP_DAL/AP_DAL.h>

#include "AP_NavEKF2.h"

// Control filter mode transitions
void NavEKF2_core::controlFilterModes()
Expand Down
5 changes: 1 addition & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
#include <AP_HAL/AP_HAL.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 magnetometer innovations to see if the heading is good enough to use GPS
Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
#include "AP_NavEKF2_core.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_core.h"
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_NavEKF2/AP_NavEKF2_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@
#include <AP_Math/vectorN.h>
#include <AP_NavEKF/AP_NavEKF_core_common.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"

Expand Down Expand Up @@ -341,7 +342,7 @@ class NavEKF2_core : public NavEKF_core_common

private:
EKFGSF_yaw *yawEstimator;
AP_DAL &dal;
class AP_DAL &dal;

// Reference to the global EKF frontend for parameters
class NavEKF2 *frontend;
Expand Down

0 comments on commit df20e35

Please sign in to comment.