mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: remove extra in_mavlink_delay from should_log function
Also return false when logging disabled
This commit is contained in:
parent
c093160ea9
commit
d58f7ada62
@ -410,6 +410,7 @@ static void telemetry_send(void)
|
||||
*/
|
||||
static bool should_log(uint32_t mask)
|
||||
{
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
||||
return false;
|
||||
}
|
||||
@ -417,9 +418,10 @@ static bool should_log(uint32_t mask)
|
||||
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
||||
// we have to set in_mavlink_delay to prevent logging while
|
||||
// writing headers
|
||||
in_mavlink_delay = true;
|
||||
start_logging();
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
return ret;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user