mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Revert "Airspeed: store reference in libraries and populate it"
This reverts commit c090ba2257
.
This commit is contained in:
parent
d8367ecbef
commit
8dad05d12e
@ -159,9 +159,6 @@ private:
|
||||
// mapping between input channels
|
||||
RCMapper rcmap;
|
||||
|
||||
// Airspeed Sensors
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
// board specific config
|
||||
AP_BoardConfig BoardConfig;
|
||||
|
||||
@ -224,12 +221,12 @@ private:
|
||||
#endif
|
||||
|
||||
AP_L1_Control L1_controller {ahrs};
|
||||
AP_TECS TECS_controller {airspeed, ahrs, aparm};
|
||||
AP_TECS TECS_controller {ahrs, aparm};
|
||||
|
||||
// Attitude to servo controllers
|
||||
AP_RollController rollController {airspeed, ahrs, aparm, DataFlash};
|
||||
AP_PitchController pitchController {airspeed, ahrs, aparm, DataFlash};
|
||||
AP_YawController yawController {airspeed, ahrs, aparm};
|
||||
AP_RollController rollController {ahrs, aparm, DataFlash};
|
||||
AP_PitchController pitchController {ahrs, aparm, DataFlash};
|
||||
AP_YawController yawController {ahrs, aparm};
|
||||
AP_SteerController steerController {ahrs};
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
@ -396,6 +393,9 @@ private:
|
||||
AP_Frsky_Telem frsky_telemetry {ahrs, battery};
|
||||
#endif
|
||||
|
||||
// Airspeed Sensors
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
// ACRO controller state
|
||||
struct {
|
||||
bool locked_roll;
|
||||
|
@ -10,8 +10,7 @@
|
||||
|
||||
class AP_PitchController {
|
||||
public:
|
||||
AP_PitchController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
||||
airspeed(aspeed),
|
||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
||||
aparm(parms),
|
||||
autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash),
|
||||
_ahrs(ahrs)
|
||||
@ -38,7 +37,7 @@ public:
|
||||
|
||||
private:
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
const AP_Airspeed &airspeed;
|
||||
AP_Airspeed airspeed;
|
||||
AP_AutoTune::ATGains gains;
|
||||
AP_AutoTune autotune;
|
||||
AP_Int16 _max_rate_neg;
|
||||
|
@ -10,9 +10,8 @@
|
||||
|
||||
class AP_RollController {
|
||||
public:
|
||||
AP_RollController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
||||
airspeed(aspeed),
|
||||
aparm(parms),
|
||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
||||
aparm(parms),
|
||||
autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash),
|
||||
_ahrs(ahrs)
|
||||
{
|
||||
@ -45,7 +44,7 @@ public:
|
||||
|
||||
private:
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
const AP_Airspeed &airspeed;
|
||||
AP_Airspeed airspeed;
|
||||
AP_AutoTune::ATGains gains;
|
||||
AP_AutoTune autotune;
|
||||
uint32_t _last_t;
|
||||
|
@ -9,8 +9,7 @@
|
||||
|
||||
class AP_YawController {
|
||||
public:
|
||||
AP_YawController(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||
airspeed(aspeed),
|
||||
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||
aparm(parms),
|
||||
_ahrs(ahrs)
|
||||
{
|
||||
@ -30,7 +29,7 @@ public:
|
||||
|
||||
private:
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
const AP_Airspeed &airspeed;
|
||||
AP_Airspeed airspeed;
|
||||
AP_Float _K_A;
|
||||
AP_Float _K_I;
|
||||
AP_Float _K_D;
|
||||
|
@ -29,8 +29,7 @@
|
||||
|
||||
class AP_TECS : public AP_SpdHgtControl {
|
||||
public:
|
||||
AP_TECS(AP_Airspeed &aspeed, AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||
airspeed(aspeed),
|
||||
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||
_ahrs(ahrs),
|
||||
aparm(parms)
|
||||
{
|
||||
@ -122,7 +121,7 @@ private:
|
||||
AP_AHRS &_ahrs;
|
||||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
const AP_Airspeed &airspeed;
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
// TECS tuning parameters
|
||||
AP_Float _hgtCompFiltOmega;
|
||||
|
Loading…
Reference in New Issue
Block a user