mirror of https://github.com/ArduPilot/ardupilot
APMrover2: stop using in_mavlink_delay as a proxy for disabling logging
This commit is contained in:
parent
6a03af8f3e
commit
aeacc11573
|
@ -1584,6 +1584,8 @@ void Rover::mavlink_delay_cb()
|
|||
}
|
||||
|
||||
in_mavlink_delay = true;
|
||||
// don't allow potentially expensive logging calls:
|
||||
DataFlash.EnableWrites(false);
|
||||
|
||||
const uint32_t tnow = millis();
|
||||
if (tnow - last_1hz > 1000) {
|
||||
|
@ -1603,6 +1605,7 @@ void Rover::mavlink_delay_cb()
|
|||
}
|
||||
check_usb_mux();
|
||||
|
||||
DataFlash.EnableWrites(true);
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
|
|
|
@ -85,9 +85,9 @@ int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
int8_t Rover::erase_logs(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
do_erase_logs();
|
||||
in_mavlink_delay = false;
|
||||
DataFlash.EnableWrites(true);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -510,9 +510,9 @@ void Rover::Log_Write_Vehicle_Startup_Messages()
|
|||
// start a new log
|
||||
void Rover::start_logging()
|
||||
{
|
||||
in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
DataFlash.StartUnstartedLogging();
|
||||
in_mavlink_delay = false;
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
#else // LOGGING_ENABLED
|
||||
|
|
|
@ -540,9 +540,6 @@ uint8_t Rover::check_digital_pin(uint8_t pin)
|
|||
*/
|
||||
bool Rover::should_log(uint32_t mask)
|
||||
{
|
||||
if (in_mavlink_delay) {
|
||||
return false;
|
||||
}
|
||||
if (!(mask & g.log_bitmask)) {
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue