Copter: remove extra in_mavlink_delay from should_log function

Also return false when logging disabled
This commit is contained in:
Randy Mackay 2014-10-17 16:07:47 +09:00
parent c093160ea9
commit d58f7ada62

View File

@ -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
}