AP_Soaring: change namespace of MultiCopter and FixedWing params

this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
Peter Barker 2022-09-30 09:10:41 +10:00 committed by Andrew Tridgell
parent 00f72575c3
commit 573604582e
4 changed files with 7 additions and 7 deletions

View File

@ -166,7 +166,7 @@ const AP_Param::GroupInfo SoaringController::var_info[] = {
AP_GROUPEND AP_GROUPEND
}; };
SoaringController::SoaringController(AP_TECS &tecs, const AP_Vehicle::FixedWing &parms) : SoaringController::SoaringController(AP_TECS &tecs, const AP_FixedWing &parms) :
_tecs(tecs), _tecs(tecs),
_vario(parms,_polarParams), _vario(parms,_polarParams),
_speedToFly(_polarParams), _speedToFly(_polarParams),

View File

@ -36,7 +36,7 @@ class SoaringController {
Variometer _vario; Variometer _vario;
SpeedToFly _speedToFly; SpeedToFly _speedToFly;
const AP_Vehicle::FixedWing &_aparm; const AP_FixedWing &_aparm;
// store aircraft location at last update // store aircraft location at last update
Vector3f _prev_update_location; Vector3f _prev_update_location;
@ -81,7 +81,7 @@ protected:
AP_Float soar_thermal_flap; AP_Float soar_thermal_flap;
public: public:
SoaringController(class AP_TECS &tecs, const AP_Vehicle::FixedWing &parms); SoaringController(class AP_TECS &tecs, const AP_FixedWing &parms);
enum class LoiterStatus { enum class LoiterStatus {
DISABLED, DISABLED,

View File

@ -6,7 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
Variometer::Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams) : Variometer::Variometer(const AP_FixedWing &parms, const PolarParams &polarParams) :
_aparm(parms), _aparm(parms),
_polarParams(polarParams) _polarParams(polarParams)
{ {

View File

@ -8,11 +8,11 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
#include <AP_AHRS/AP_AHRS.h> #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 <AP_Vehicle/AP_Vehicle.h> #include <AP_Vehicle/AP_FixedWing.h>
class Variometer { class Variometer {
const AP_Vehicle::FixedWing &_aparm; const AP_FixedWing &_aparm;
// store time of last update // store time of last update
uint64_t _prev_update_time; uint64_t _prev_update_time;
@ -53,7 +53,7 @@ public:
AP_Float B; AP_Float B;
}; };
Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams); Variometer(const AP_FixedWing &parms, const PolarParams &polarParams);
float alt; float alt;
float reading; float reading;