From c090ba2257e59d7dd49c474f408e4cdf1c34ba60 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 4 Aug 2016 11:06:44 -0700 Subject: [PATCH] Airspeed: store reference in libraries and populate it - also had to move the initial definition in plane.h so it happened before the others. --- ArduPlane/Plane.h | 14 +++++++------- libraries/APM_Control/AP_PitchController.h | 5 +++-- libraries/APM_Control/AP_RollController.h | 7 ++++--- libraries/APM_Control/AP_YawController.h | 5 +++-- libraries/AP_TECS/AP_TECS.h | 5 +++-- 5 files changed, 20 insertions(+), 16 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index acd5c835ad..5760901d89 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -159,6 +159,9 @@ private: // mapping between input channels RCMapper rcmap; + // Airspeed Sensors + AP_Airspeed airspeed; + // board specific config AP_BoardConfig BoardConfig; @@ -221,12 +224,12 @@ private: #endif AP_L1_Control L1_controller {ahrs}; - AP_TECS TECS_controller {ahrs, aparm}; + AP_TECS TECS_controller {airspeed, ahrs, aparm}; // Attitude to servo controllers - AP_RollController rollController {ahrs, aparm, DataFlash}; - AP_PitchController pitchController {ahrs, aparm, DataFlash}; - AP_YawController yawController {ahrs, aparm}; + AP_RollController rollController {airspeed, ahrs, aparm, DataFlash}; + AP_PitchController pitchController {airspeed, ahrs, aparm, DataFlash}; + AP_YawController yawController {airspeed, ahrs, aparm}; AP_SteerController steerController {ahrs}; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -393,9 +396,6 @@ private: AP_Frsky_Telem frsky_telemetry {ahrs, battery}; #endif - // Airspeed Sensors - AP_Airspeed airspeed; - // ACRO controller state struct { bool locked_roll; diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index f25d14c136..fc97306af5 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -10,7 +10,8 @@ class AP_PitchController { public: - AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) : + AP_PitchController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) : + airspeed(aspeed), aparm(parms), autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash), _ahrs(ahrs) @@ -37,7 +38,7 @@ public: private: const AP_Vehicle::FixedWing &aparm; - AP_Airspeed airspeed; + const AP_Airspeed &airspeed; AP_AutoTune::ATGains gains; AP_AutoTune autotune; AP_Int16 _max_rate_neg; diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 7212dae9e9..b6b391ac14 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -10,8 +10,9 @@ class AP_RollController { public: - AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) : - aparm(parms), + AP_RollController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) : + airspeed(aspeed), + aparm(parms), autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash), _ahrs(ahrs) { @@ -44,7 +45,7 @@ public: private: const AP_Vehicle::FixedWing &aparm; - AP_Airspeed airspeed; + const AP_Airspeed &airspeed; AP_AutoTune::ATGains gains; AP_AutoTune autotune; uint32_t _last_t; diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index 23727e911e..8edf60aa5f 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -9,7 +9,8 @@ class AP_YawController { public: - AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : + AP_YawController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : + airspeed(aspeed), aparm(parms), _ahrs(ahrs) { @@ -29,7 +30,7 @@ public: private: const AP_Vehicle::FixedWing &aparm; - AP_Airspeed airspeed; + const AP_Airspeed &airspeed; AP_Float _K_A; AP_Float _K_I; AP_Float _K_D; diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 814ec07c78..923f6266c5 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -29,7 +29,8 @@ class AP_TECS : public AP_SpdHgtControl { public: - AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : + AP_TECS(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) : + airspeed(aspeed), _ahrs(ahrs), aparm(parms) { @@ -121,7 +122,7 @@ private: AP_AHRS &_ahrs; const AP_Vehicle::FixedWing &aparm; - AP_Airspeed airspeed; + const AP_Airspeed &airspeed; // TECS tuning parameters AP_Float _hgtCompFiltOmega;