AP_Soaring: tidy includes

This commit is contained in:
Peter Barker 2022-11-07 10:20:59 +11:00 committed by Peter Barker
parent ad32805213
commit 162d93c742
2 changed files with 14 additions and 13 deletions

View File

@ -1,11 +1,12 @@
#include "AP_Soaring.h"
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
#include <stdint.h>
extern const AP_HAL::HAL& hal;
#if HAL_SOARING_ENABLED
#include <AP_Logger/AP_Logger.h>
#include <AP_TECS/AP_TECS.h>
#include <GCS_MAVLink/GCS.h>
#include <stdint.h>
// ArduSoar parameters
const AP_Param::GroupInfo SoaringController::var_info[] = {
// @Param: ENABLE

View File

@ -9,13 +9,7 @@
#pragma once
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include "ExtendedKalmanFilter.h"
#include "Variometer.h"
#include <AP_TECS/AP_TECS.h>
#include "SpeedToFly.h"
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef HAL_SOARING_ENABLED
#define HAL_SOARING_ENABLED !HAL_MINIMIZE_FEATURES
@ -23,6 +17,12 @@
#if HAL_SOARING_ENABLED
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include "ExtendedKalmanFilter.h"
#include "Variometer.h"
#include "SpeedToFly.h"
#define INITIAL_THERMAL_RADIUS 80.0
#define INITIAL_STRENGTH_COVARIANCE 0.0049
#define INITIAL_RADIUS_COVARIANCE 400.0
@ -32,7 +32,7 @@
class SoaringController {
Variometer::PolarParams _polarParams;
ExtendedKalmanFilter _ekf{};
AP_TECS &_tecs;
class AP_TECS &_tecs;
Variometer _vario;
SpeedToFly _speedToFly;
@ -81,7 +81,7 @@ protected:
AP_Float soar_thermal_flap;
public:
SoaringController(AP_TECS &tecs, const AP_Vehicle::FixedWing &parms);
SoaringController(class AP_TECS &tecs, const AP_Vehicle::FixedWing &parms);
enum class LoiterStatus {
DISABLED,