mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: correct includes
This commit is contained in:
parent
032b7c81e5
commit
6b701ae3b3
|
@ -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>
|
||||
|
||||
/*
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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>
|
||||
|
||||
|
|
|
@ -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>
|
||||
|
|
|
@ -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 *
|
||||
|
|
|
@ -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>
|
||||
|
|
|
@ -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>
|
||||
|
|
|
@ -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
|
||||
|
@ -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);
|
||||
|
@ -445,7 +446,7 @@ private:
|
|||
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)
|
||||
|
|
Loading…
Reference in New Issue