Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tidy EKF-related #include lists #14933

Merged
merged 3 commits into from Aug 7, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
5 changes: 3 additions & 2 deletions libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
Expand Up @@ -21,11 +21,12 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_AHRS.h"
#include "AP_AHRS_View.h"
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Module/AP_Module.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

#if AP_AHRS_NAVEKF_AVAILABLE

Expand Down
4 changes: 1 addition & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2.cpp
@@ -1,11 +1,9 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2_core.h"
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <new>

/*
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp
Expand Up @@ -3,9 +3,6 @@
#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>

#include <stdio.h>

extern const AP_HAL::HAL& hal;

Expand Down
4 changes: 1 addition & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
Expand Up @@ -3,9 +3,7 @@
#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>

#include <stdio.h>

Expand Down Expand Up @@ -580,4 +578,4 @@ void NavEKF2_core::runYawEstimatorCorrection()
void NavEKF2_core::EKFGSF_requestYawReset()
{
EKFGSF_yaw_reset_request_ms = imuSampleTime_ms;
}
}
4 changes: 0 additions & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp
Expand Up @@ -2,12 +2,8 @@

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

#include <stdio.h>

extern const AP_HAL::HAL& hal;

/********************************************************
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
@@ -1,6 +1,5 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
Expand All @@ -11,8 +10,6 @@
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>

#include <stdio.h>

extern const AP_HAL::HAL& hal;


Expand Down
4 changes: 0 additions & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp
Expand Up @@ -2,10 +2,6 @@

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>

#include <stdio.h>

extern const AP_HAL::HAL& hal;

Expand Down
4 changes: 0 additions & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp
@@ -1,14 +1,10 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_RangeFinder/AP_RangeFinder.h>

#include <stdio.h>

extern const AP_HAL::HAL& hal;


Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp
Expand Up @@ -2,8 +2,6 @@

#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
#include <AP_GPS/AP_GPS.h>
Expand Down
9 changes: 0 additions & 9 deletions libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp
@@ -1,14 +1,5 @@
#include <AP_HAL/AP_HAL.h>

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

#include <stdio.h>

extern const AP_HAL::HAL& hal;

/********************************************************
* FUSE MEASURED_DATA *
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp
@@ -1,14 +1,11 @@
#include <AP_HAL/AP_HAL.h>

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

#include <stdio.h>

extern const AP_HAL::HAL& hal;


Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
Expand Up @@ -3,12 +3,9 @@
#include "AP_NavEKF2.h"
#include "AP_NavEKF2_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>

#include <stdio.h>

extern const AP_HAL::HAL& hal;

#define earthRate 0.000072921f // earth rotation rate (rad/sec)
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_NavEKF2/AP_NavEKF2_core.h
Expand Up @@ -29,12 +29,12 @@

#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include "AP_NavEKF2.h"
#include <stdio.h>
#include <AP_Math/vectorN.h>
#include <AP_NavEKF/AP_NavEKF_core_common.h>
#include <AP_NavEKF2/AP_NavEKF2_Buffer.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#include "AP_NavEKF/EKFGSF_yaw.h"

// GPS pre-flight check bit locations
Expand Down Expand Up @@ -72,7 +72,7 @@ class NavEKF2_core : public NavEKF_core_common
{
public:
// Constructor
NavEKF2_core(NavEKF2 *_frontend);
NavEKF2_core(class NavEKF2 *_frontend);

// setup this core backend
bool setup_core(uint8_t _imu_index, uint8_t _core_index);
Expand Down Expand Up @@ -363,7 +363,7 @@ class NavEKF2_core : public NavEKF_core_common
EKFGSF_yaw *yawEstimator;

// Reference to the global EKF frontend for parameters
NavEKF2 *frontend;
class NavEKF2 *frontend;
uint8_t imu_index; // preferred IMU index
uint8_t gyro_index_active; // active gyro index (in case preferred fails)
uint8_t accel_index_active; // active accel index (in case preferred fails)
Expand Down
5 changes: 2 additions & 3 deletions libraries/AP_NavEKF3/AP_NavEKF3.cpp
@@ -1,11 +1,10 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3_core.h"
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

#include <new>

/*
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp
Expand Up @@ -3,7 +3,6 @@
#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>

extern const AP_HAL::HAL& hal;

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
Expand Up @@ -3,9 +3,7 @@
#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>

extern const AP_HAL::HAL& hal;

Expand Down
7 changes: 0 additions & 7 deletions libraries/AP_NavEKF3/AP_NavEKF3_GyroBias.cpp
@@ -1,11 +1,4 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>

extern const AP_HAL::HAL& hal;

// reset the body axis gyro bias states to zero and re-initialise the corresponding covariances
// Assume that the calibration is performed to an accuracy of 0.5 deg/sec which will require averaging under static conditions
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
Expand Up @@ -2,8 +2,6 @@

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp
@@ -1,15 +1,14 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_Logger/AP_Logger.h>

extern const AP_HAL::HAL& hal;

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp
Expand Up @@ -2,8 +2,6 @@

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp
@@ -1,9 +1,7 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_RangeFinder/AP_RangeFinder.h>

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp
Expand Up @@ -2,8 +2,6 @@

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
Expand Down
7 changes: 0 additions & 7 deletions libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp
@@ -1,12 +1,5 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>

extern const AP_HAL::HAL& hal;

/********************************************************
* FUSE MEASURED_DATA *
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp
@@ -1,6 +1,5 @@
#include <AP_HAL/AP_HAL.h>

#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_core.cpp
Expand Up @@ -3,7 +3,6 @@
#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
Expand Down
7 changes: 4 additions & 3 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Expand Up @@ -28,11 +28,12 @@

#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include "AP_NavEKF3.h"
#include <AP_Math/vectorN.h>
#include <AP_NavEKF/AP_NavEKF_core_common.h>
#include <AP_NavEKF3/AP_NavEKF3_Buffer.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#include "AP_NavEKF/EKFGSF_yaw.h"

// GPS pre-flight check bit locations
Expand Down Expand Up @@ -91,7 +92,7 @@ class NavEKF3_core : public NavEKF_core_common
{
public:
// Constructor
NavEKF3_core(NavEKF3 *_frontend);
NavEKF3_core(class NavEKF3 *_frontend);

// setup this core backend
bool setup_core(uint8_t _imu_index, uint8_t _core_index);
Expand Down Expand Up @@ -445,7 +446,7 @@ class NavEKF3_core : public NavEKF_core_common
EKFGSF_yaw *yawEstimator;

// Reference to the global EKF frontend for parameters
NavEKF3 *frontend;
class NavEKF3 *frontend;
uint8_t imu_index; // preferred IMU index
uint8_t gyro_index_active; // active gyro index (in case preferred fails)
uint8_t accel_index_active; // active accel index (in case preferred fails)
Expand Down