mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Plane: prevent log corruption when new log started
This commit is contained in:
parent
921f923c5f
commit
cf09fef1db
@ -2223,7 +2223,7 @@ mission_failed:
|
|||||||
static void mavlink_delay_cb()
|
static void mavlink_delay_cb()
|
||||||
{
|
{
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
static uint32_t last_1hz, last_50hz, last_5s;
|
||||||
if (!gcs[0].initialised) return;
|
if (!gcs[0].initialised || in_mavlink_delay) return;
|
||||||
|
|
||||||
in_mavlink_delay = true;
|
in_mavlink_delay = true;
|
||||||
|
|
||||||
|
@ -610,7 +610,7 @@ static void servo_write(uint8_t ch, uint16_t pwm)
|
|||||||
*/
|
*/
|
||||||
static bool should_log(uint32_t mask)
|
static bool should_log(uint32_t mask)
|
||||||
{
|
{
|
||||||
if (!(mask & g.log_bitmask)) {
|
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
bool armed;
|
bool armed;
|
||||||
@ -623,7 +623,11 @@ static bool should_log(uint32_t mask)
|
|||||||
}
|
}
|
||||||
bool ret = armed || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
bool ret = armed || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
||||||
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
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();
|
start_logging();
|
||||||
|
in_mavlink_delay = false;
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user