mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_NavEKF2: correct includes
This commit is contained in:
parent
37340b846d
commit
032b7c81e5
@ -1,11 +1,9 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_Vehicle/AP_Vehicle.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_GPS/AP_GPS.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
|
||||||
#include <new>
|
#include <new>
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -3,9 +3,6 @@
|
|||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
@ -580,4 +578,4 @@ void NavEKF2_core::runYawEstimatorCorrection()
|
|||||||
void NavEKF2_core::EKFGSF_requestYawReset()
|
void NavEKF2_core::EKFGSF_requestYawReset()
|
||||||
{
|
{
|
||||||
EKFGSF_yaw_reset_request_ms = imuSampleTime_ms;
|
EKFGSF_yaw_reset_request_ms = imuSampleTime_ms;
|
||||||
}
|
}
|
||||||
|
@ -2,12 +2,8 @@
|
|||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
/********************************************************
|
/********************************************************
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
@ -11,8 +10,6 @@
|
|||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
#include <AP_Compass/AP_Compass.h>
|
#include <AP_Compass/AP_Compass.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
|
||||||
|
@ -2,10 +2,6 @@
|
|||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.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;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -1,14 +1,10 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
|
||||||
|
@ -2,8 +2,6 @@
|
|||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.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.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
@ -1,14 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.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 *
|
* FUSE MEASURED_DATA *
|
||||||
|
@ -1,14 +1,11 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#include "AP_NavEKF2.h"
|
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
|
||||||
|
@ -3,12 +3,9 @@
|
|||||||
#include "AP_NavEKF2.h"
|
#include "AP_NavEKF2.h"
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define earthRate 0.000072921f // earth rotation rate (rad/sec)
|
#define earthRate 0.000072921f // earth rotation rate (rad/sec)
|
||||||
|
@ -29,12 +29,12 @@
|
|||||||
|
|
||||||
#include <AP_Common/Location.h>
|
#include <AP_Common/Location.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include "AP_NavEKF2.h"
|
|
||||||
#include <stdio.h>
|
|
||||||
#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_NavEKF2/AP_NavEKF2_Buffer.h>
|
#include <AP_NavEKF2/AP_NavEKF2_Buffer.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
|
||||||
#include "AP_NavEKF/EKFGSF_yaw.h"
|
#include "AP_NavEKF/EKFGSF_yaw.h"
|
||||||
|
|
||||||
// GPS pre-flight check bit locations
|
// GPS pre-flight check bit locations
|
||||||
@ -72,7 +72,7 @@ class NavEKF2_core : public NavEKF_core_common
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructor
|
// Constructor
|
||||||
NavEKF2_core(NavEKF2 *_frontend);
|
NavEKF2_core(class NavEKF2 *_frontend);
|
||||||
|
|
||||||
// setup this core backend
|
// setup this core backend
|
||||||
bool setup_core(uint8_t _imu_index, uint8_t _core_index);
|
bool setup_core(uint8_t _imu_index, uint8_t _core_index);
|
||||||
@ -363,7 +363,7 @@ private:
|
|||||||
EKFGSF_yaw *yawEstimator;
|
EKFGSF_yaw *yawEstimator;
|
||||||
|
|
||||||
// Reference to the global EKF frontend for parameters
|
// Reference to the global EKF frontend for parameters
|
||||||
NavEKF2 *frontend;
|
class NavEKF2 *frontend;
|
||||||
uint8_t imu_index; // preferred IMU index
|
uint8_t imu_index; // preferred IMU index
|
||||||
uint8_t gyro_index_active; // active gyro index (in case preferred fails)
|
uint8_t gyro_index_active; // active gyro index (in case preferred fails)
|
||||||
uint8_t accel_index_active; // active accel index (in case preferred fails)
|
uint8_t accel_index_active; // active accel index (in case preferred fails)
|
||||||
|
Loading…
Reference in New Issue
Block a user