mirror of https://github.com/ArduPilot/ardupilot
APM_Control: stop taking reference to dataflash, use singleton
This commit is contained in:
parent
ee13110ad0
commit
d1f5bcb1ab
|
@ -67,13 +67,11 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
// constructor
|
||||
AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
|
||||
const AP_Vehicle::FixedWing &parms,
|
||||
DataFlash_Class &_dataflash) :
|
||||
const AP_Vehicle::FixedWing &parms) :
|
||||
running(false),
|
||||
current(_gains),
|
||||
type(_type),
|
||||
aparm(parms),
|
||||
dataflash(_dataflash),
|
||||
saturated_surfaces(false)
|
||||
{}
|
||||
|
||||
|
@ -268,7 +266,8 @@ void AP_AutoTune::check_save(void)
|
|||
*/
|
||||
void AP_AutoTune::log_param_change(float v, const char *suffix)
|
||||
{
|
||||
if (!dataflash.logging_started()) {
|
||||
DataFlash_Class *dataflash = DataFlash_Class::instance();
|
||||
if (!dataflash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
char key[AP_MAX_NAME_SIZE+1];
|
||||
|
@ -280,7 +279,7 @@ void AP_AutoTune::log_param_change(float v, const char *suffix)
|
|||
strncpy(&key[9], suffix, AP_MAX_NAME_SIZE-9);
|
||||
}
|
||||
key[AP_MAX_NAME_SIZE] = 0;
|
||||
dataflash.Log_Write_Parameter(key, v);
|
||||
dataflash->Log_Write_Parameter(key, v);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -328,7 +327,8 @@ void AP_AutoTune::save_gains(const ATGains &v)
|
|||
|
||||
void AP_AutoTune::write_log(float servo, float demanded, float achieved)
|
||||
{
|
||||
if (!dataflash.logging_started()) {
|
||||
DataFlash_Class *dataflash = DataFlash_Class::instance();
|
||||
if (!dataflash->logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -342,5 +342,5 @@ void AP_AutoTune::write_log(float servo, float demanded, float achieved)
|
|||
achieved : achieved,
|
||||
P : current.P.get()
|
||||
};
|
||||
dataflash.WriteBlock(&pkt, sizeof(pkt));
|
||||
dataflash->WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
|
|
@ -34,7 +34,7 @@ public:
|
|||
|
||||
|
||||
// constructor
|
||||
AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash);
|
||||
AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms);
|
||||
|
||||
// called when autotune mode is entered
|
||||
void start(void);
|
||||
|
@ -59,8 +59,6 @@ private:
|
|||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
|
||||
DataFlash_Class &dataflash;
|
||||
|
||||
// did we saturate surfaces?
|
||||
bool saturated_surfaces:1;
|
||||
|
||||
|
|
|
@ -9,9 +9,9 @@
|
|||
|
||||
class AP_PitchController {
|
||||
public:
|
||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
|
|
@ -9,9 +9,9 @@
|
|||
|
||||
class AP_RollController {
|
||||
public:
|
||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
|
Loading…
Reference in New Issue