From c93aea24c6ed7d160b48dc399dac930574ca06a8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 28 Feb 2018 15:42:09 +1100 Subject: [PATCH] AP_Soaring: correct compiler warnings In file included from ../../libraries/AP_Soaring/AP_Soaring.cpp:1: ../../libraries/AP_Soaring/AP_Soaring.h:32:34: warning: private field '_aparm' is not used [-Wunused-private-field] const AP_Vehicle::FixedWing &_aparm; --- libraries/AP_Soaring/AP_Soaring.cpp | 3 +-- libraries/AP_Soaring/AP_Soaring.h | 1 - libraries/AP_Soaring/Variometer.cpp | 3 +-- libraries/AP_Soaring/Variometer.h | 3 +-- 4 files changed, 3 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 59c5581005..6764679c2a 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -131,8 +131,7 @@ const AP_Param::GroupInfo SoaringController::var_info[] = { SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) : _ahrs(ahrs), _spdHgt(spdHgt), - _aparm(parms), - _vario(ahrs,spdHgt,parms), + _vario(ahrs,parms), _loiter_rad(parms.loiter_radius), _throttle_suppressed(true) { diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index d78e04bf9d..11b43b1a15 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -29,7 +29,6 @@ class SoaringController { ExtendedKalmanFilter _ekf{}; AP_AHRS &_ahrs; AP_SpdHgtControl &_spdHgt; - const AP_Vehicle::FixedWing &_aparm; Variometer _vario; // store aircraft location at last update diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 179ebeeb93..fe7c9c48b1 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -4,9 +4,8 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. */ #include "Variometer.h" -Variometer::Variometer(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) : +Variometer::Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : _ahrs(ahrs), - _spdHgt(spdHgt), _aparm(parms), new_data(false) { diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index 4f5bb74658..fea389a484 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -17,7 +17,6 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. class Variometer { AP_AHRS &_ahrs; - AP_SpdHgtControl &_spdHgt; const AP_Vehicle::FixedWing &_aparm; // store time of last update @@ -31,7 +30,7 @@ class Variometer { float _last_total_E; public: - Variometer(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms); + Variometer(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms); float alt; float reading; float filtered_reading;