Airspeed: store reference in libraries and populate it

- also had to move the initial definition in plane.h so it happened before the others.
This commit is contained in:
Tom Pittenger 2016-08-04 11:06:44 -07:00
parent 96b287735f
commit c090ba2257
5 changed files with 20 additions and 16 deletions

View File

@ -159,6 +159,9 @@ private:
// mapping between input channels // mapping between input channels
RCMapper rcmap; RCMapper rcmap;
// Airspeed Sensors
AP_Airspeed airspeed;
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig;
@ -221,12 +224,12 @@ private:
#endif #endif
AP_L1_Control L1_controller {ahrs}; AP_L1_Control L1_controller {ahrs};
AP_TECS TECS_controller {ahrs, aparm}; AP_TECS TECS_controller {airspeed, ahrs, aparm};
// Attitude to servo controllers // Attitude to servo controllers
AP_RollController rollController {ahrs, aparm, DataFlash}; AP_RollController rollController {airspeed, ahrs, aparm, DataFlash};
AP_PitchController pitchController {ahrs, aparm, DataFlash}; AP_PitchController pitchController {airspeed, ahrs, aparm, DataFlash};
AP_YawController yawController {ahrs, aparm}; AP_YawController yawController {airspeed, ahrs, aparm};
AP_SteerController steerController {ahrs}; AP_SteerController steerController {ahrs};
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
@ -393,9 +396,6 @@ private:
AP_Frsky_Telem frsky_telemetry {ahrs, battery}; AP_Frsky_Telem frsky_telemetry {ahrs, battery};
#endif #endif
// Airspeed Sensors
AP_Airspeed airspeed;
// ACRO controller state // ACRO controller state
struct { struct {
bool locked_roll; bool locked_roll;

View File

@ -10,7 +10,8 @@
class AP_PitchController { class AP_PitchController {
public: 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), aparm(parms),
autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash), autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash),
_ahrs(ahrs) _ahrs(ahrs)
@ -37,7 +38,7 @@ public:
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_Vehicle::FixedWing &aparm;
AP_Airspeed airspeed; const AP_Airspeed &airspeed;
AP_AutoTune::ATGains gains; AP_AutoTune::ATGains gains;
AP_AutoTune autotune; AP_AutoTune autotune;
AP_Int16 _max_rate_neg; AP_Int16 _max_rate_neg;

View File

@ -10,8 +10,9 @@
class AP_RollController { class AP_RollController {
public: public:
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) : AP_RollController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
aparm(parms), airspeed(aspeed),
aparm(parms),
autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash), autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash),
_ahrs(ahrs) _ahrs(ahrs)
{ {
@ -44,7 +45,7 @@ public:
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_Vehicle::FixedWing &aparm;
AP_Airspeed airspeed; const AP_Airspeed &airspeed;
AP_AutoTune::ATGains gains; AP_AutoTune::ATGains gains;
AP_AutoTune autotune; AP_AutoTune autotune;
uint32_t _last_t; uint32_t _last_t;

View File

@ -9,7 +9,8 @@
class AP_YawController { class AP_YawController {
public: 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), aparm(parms),
_ahrs(ahrs) _ahrs(ahrs)
{ {
@ -29,7 +30,7 @@ public:
private: private:
const AP_Vehicle::FixedWing &aparm; const AP_Vehicle::FixedWing &aparm;
AP_Airspeed airspeed; const AP_Airspeed &airspeed;
AP_Float _K_A; AP_Float _K_A;
AP_Float _K_I; AP_Float _K_I;
AP_Float _K_D; AP_Float _K_D;

View File

@ -29,7 +29,8 @@
class AP_TECS : public AP_SpdHgtControl { class AP_TECS : public AP_SpdHgtControl {
public: 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), _ahrs(ahrs),
aparm(parms) aparm(parms)
{ {
@ -121,7 +122,7 @@ private:
AP_AHRS &_ahrs; AP_AHRS &_ahrs;
const AP_Vehicle::FixedWing &aparm; const AP_Vehicle::FixedWing &aparm;
AP_Airspeed airspeed; const AP_Airspeed &airspeed;
// TECS tuning parameters // TECS tuning parameters
AP_Float _hgtCompFiltOmega; AP_Float _hgtCompFiltOmega;