mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: suspend logging while disarmed
This commit is contained in:
parent
a53d1075ec
commit
84881470b1
@ -799,7 +799,8 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
||||
// start a new log
|
||||
static void start_logging()
|
||||
{
|
||||
if (g.log_bitmask != 0 && !ap.logging_started) {
|
||||
if (g.log_bitmask != 0) {
|
||||
if (!ap.logging_started) {
|
||||
ap.logging_started = true;
|
||||
DataFlash.StartNewLog();
|
||||
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
|
||||
@ -813,6 +814,9 @@ static void start_logging()
|
||||
// log the flight mode
|
||||
Log_Write_Mode(control_mode);
|
||||
}
|
||||
// enable writes
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
}
|
||||
|
||||
#else // LOGGING_ENABLED
|
||||
|
@ -503,6 +503,9 @@ static void init_disarm_motors()
|
||||
// log disarm to the dataflash
|
||||
Log_Write_Event(DATA_DISARMED);
|
||||
|
||||
// suspend logging
|
||||
DataFlash.EnableWrites(false);
|
||||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user