AP_Soaring: stop taking AHRS as constructor argument

... use singleton instead
This commit is contained in:
Peter Barker 2020-05-05 14:41:17 +10:00 committed by Andrew Tridgell
parent f1f30a2fee
commit 69093aa7b1
4 changed files with 11 additions and 11 deletions

View File

@ -138,10 +138,9 @@ const AP_Param::GroupInfo SoaringController::var_info[] = {
AP_GROUPEND
};
SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) :
_ahrs(ahrs),
SoaringController::SoaringController(AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) :
_spdHgt(spdHgt),
_vario(ahrs,parms),
_vario(parms),
_aparm(parms),
_throttle_suppressed(true)
{
@ -153,7 +152,7 @@ SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, co
void SoaringController::get_target(Location &wp)
{
wp = _ahrs.get_home();
wp = AP::ahrs().get_home();
wp.offset(_position_x_filter.get(), _position_y_filter.get());
}
@ -260,7 +259,8 @@ void SoaringController::init_thermalling()
const MatrixN<float,4> p{init_p};
Vector3f position;
const AP_AHRS &_ahrs = AP::ahrs();
if (!_ahrs.get_relative_position_NED_home(position)) {
return;
}
@ -301,6 +301,7 @@ void SoaringController::update_thermalling()
Vector3f current_position;
const AP_AHRS &_ahrs = AP::ahrs();
if (!_ahrs.get_relative_position_NED_home(current_position)) {
return;
}

View File

@ -25,7 +25,6 @@
class SoaringController {
ExtendedKalmanFilter _ekf{};
AP_AHRS &_ahrs;
AP_SpdHgtControl &_spdHgt;
Variometer _vario;
const AP_Vehicle::FixedWing &_aparm;
@ -74,7 +73,7 @@ protected:
AP_Float max_drift;
public:
SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms);
SoaringController(AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms);
enum class LoiterStatus {
DISABLED,

View File

@ -6,8 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
#include <AP_Logger/AP_Logger.h>
Variometer::Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
_ahrs(ahrs),
Variometer::Variometer(const AP_Vehicle::FixedWing &parms) :
_aparm(parms)
{
_climb_filter = LowPassFilter<float>(1.0/60.0);
@ -17,6 +16,8 @@ Variometer::Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
void Variometer::update(const float polar_K, const float polar_Cd0, const float polar_B)
{
const AP_AHRS &_ahrs = AP::ahrs();
_ahrs.get_relative_position_D_home(alt);
alt = -alt;

View File

@ -16,7 +16,6 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
class Variometer {
AP_AHRS &_ahrs;
const AP_Vehicle::FixedWing &_aparm;
// store time of last update
@ -43,7 +42,7 @@ class Variometer {
LowPassFilter<float> _vdot_filter2;
public:
Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms);
Variometer(const AP_Vehicle::FixedWing &parms);
float alt;
float reading;
float filtered_reading;