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;
This commit is contained in:
Peter Barker 2018-02-28 15:42:09 +11:00 committed by Randy Mackay
parent 9b23b469cf
commit c93aea24c6
4 changed files with 3 additions and 7 deletions

View File

@ -131,8 +131,7 @@ const AP_Param::GroupInfo SoaringController::var_info[] = {
SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) : SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) :
_ahrs(ahrs), _ahrs(ahrs),
_spdHgt(spdHgt), _spdHgt(spdHgt),
_aparm(parms), _vario(ahrs,parms),
_vario(ahrs,spdHgt,parms),
_loiter_rad(parms.loiter_radius), _loiter_rad(parms.loiter_radius),
_throttle_suppressed(true) _throttle_suppressed(true)
{ {

View File

@ -29,7 +29,6 @@ class SoaringController {
ExtendedKalmanFilter _ekf{}; ExtendedKalmanFilter _ekf{};
AP_AHRS &_ahrs; AP_AHRS &_ahrs;
AP_SpdHgtControl &_spdHgt; AP_SpdHgtControl &_spdHgt;
const AP_Vehicle::FixedWing &_aparm;
Variometer _vario; Variometer _vario;
// store aircraft location at last update // store aircraft location at last update

View File

@ -4,9 +4,8 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
*/ */
#include "Variometer.h" #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), _ahrs(ahrs),
_spdHgt(spdHgt),
_aparm(parms), _aparm(parms),
new_data(false) new_data(false)
{ {

View File

@ -17,7 +17,6 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
class Variometer { class Variometer {
AP_AHRS &_ahrs; AP_AHRS &_ahrs;
AP_SpdHgtControl &_spdHgt;
const AP_Vehicle::FixedWing &_aparm; const AP_Vehicle::FixedWing &_aparm;
// store time of last update // store time of last update
@ -31,7 +30,7 @@ class Variometer {
float _last_total_E; float _last_total_E;
public: 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 alt;
float reading; float reading;
float filtered_reading; float filtered_reading;