mirror of https://github.com/ArduPilot/ardupilot
Copter: remove extra in_mavlink_delay from should_log function
Also return false when logging disabled
This commit is contained in:
parent
c3d839456b
commit
dcf72e9b78
|
@ -409,6 +409,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;
|
||||
}
|
||||
|
@ -416,9 +417,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