mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Soaring: remove use of AP_AHRS from most headers
don't need to know the details, just that it is a class
This commit is contained in:
parent
e19ae3ec01
commit
771696e7d5
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#if HAL_SOARING_ENABLED
|
#if HAL_SOARING_ENABLED
|
||||||
|
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_TECS/AP_TECS.h>
|
#include <AP_TECS/AP_TECS.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
@ -4,6 +4,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
|
|||||||
*/
|
*/
|
||||||
#include "Variometer.h"
|
#include "Variometer.h"
|
||||||
|
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) :
|
Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) :
|
||||||
|
@ -5,10 +5,11 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <Filter/AverageFilter.h>
|
#include <Filter/AverageFilter.h>
|
||||||
|
#include <Filter/LowPassFilter.h>
|
||||||
#include <AP_Vehicle/AP_FixedWing.h>
|
#include <AP_Vehicle/AP_FixedWing.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
|
||||||
class Variometer {
|
class Variometer {
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user