mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_AHRS: include cleanups
This commit is contained in:
parent
2ab2555e0b
commit
24099f9a2d
@ -22,9 +22,11 @@
|
|||||||
#include "AP_AHRS.h"
|
#include "AP_AHRS.h"
|
||||||
#include "AP_AHRS_View.h"
|
#include "AP_AHRS_View.h"
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
||||||
#include <AP_Module/AP_Module.h>
|
#include <AP_Module/AP_Module.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_Notify/AP_Notify.h>
|
#include <AP_Notify/AP_Notify.h>
|
||||||
|
@ -16,7 +16,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* NavEKF based AHRS (Attitude Heading Reference System) interface for
|
* AHRS (Attitude Heading Reference System) frontend interface for
|
||||||
* ArduPilot
|
* ArduPilot
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
@ -36,14 +36,10 @@
|
|||||||
#define AP_AHRS_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
#define AP_AHRS_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "AP_AHRS.h"
|
|
||||||
|
|
||||||
#if AP_AHRS_SIM_ENABLED
|
#if AP_AHRS_SIM_ENABLED
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
|
||||||
|
|
||||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||||
#include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
|
#include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
|
||||||
|
@ -16,10 +16,13 @@
|
|||||||
*/
|
*/
|
||||||
#include "AP_AHRS.h"
|
#include "AP_AHRS.h"
|
||||||
#include "AP_AHRS_View.h"
|
#include "AP_AHRS_View.h"
|
||||||
|
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
#include <AP_Compass/AP_Compass.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -22,11 +22,8 @@
|
|||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <AP_Compass/AP_Compass.h>
|
|
||||||
#include <AP_Airspeed/AP_Airspeed.h>
|
#include <AP_Airspeed/AP_Airspeed.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
|
||||||
#include <AP_Common/Location.h>
|
|
||||||
|
|
||||||
class OpticalFlow;
|
class OpticalFlow;
|
||||||
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
||||||
@ -204,10 +201,10 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
virtual bool set_origin(const Location &loc) {
|
virtual bool set_origin(const struct Location &loc) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
virtual bool get_origin(Location &ret) const = 0;
|
virtual bool get_origin(struct Location &ret) const = 0;
|
||||||
|
|
||||||
// return a position relative to origin in meters, North/East/Down
|
// return a position relative to origin in meters, North/East/Down
|
||||||
// order. This will only be accurate if have_inertial_nav() is
|
// order. This will only be accurate if have_inertial_nav() is
|
||||||
|
@ -25,6 +25,7 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
Loading…
Reference in New Issue
Block a user