diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 47a5af9203..4d645bf191 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -448,11 +448,6 @@ void Copter::Log_Write_Startup() time_us : hal.scheduler->micros64() }; DataFlash.WriteBlock(&pkt, sizeof(pkt)); - - // write all commands to the dataflash as well - if (should_log(MASK_LOG_CMD)) { - DataFlash.Log_Write_EntireMission(mission); - } } struct PACKED log_Event { @@ -755,6 +750,11 @@ void Copter::start_logging() DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING)); + // write mission commands + if (MASK_LOG_CMD & g.log_bitmask) { + DataFlash.Log_Write_EntireMission(mission); + } + Log_Write_Startup(); // log the flight mode diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index ccc0971241..a3ebab5497 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -822,9 +822,6 @@ void Copter::init_disarm_motors() gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS")); #endif - // send disarm command to motors - motors.armed(false); - // save compass offsets learned by the EKF Vector3f magOffsets; if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) { @@ -840,12 +837,15 @@ void Copter::init_disarm_motors() set_land_complete(true); set_land_complete_maybe(true); - // reset the mission - mission.reset(); - // log disarm to the dataflash Log_Write_Event(DATA_DISARMED); + // send disarm command to motors + motors.armed(false); + + // reset the mission + mission.reset(); + // suspend logging if (!(g.log_bitmask & MASK_LOG_WHEN_DISARMED)) { DataFlash.EnableWrites(false); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index a60ae9f66f..490976a5ee 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -255,10 +255,6 @@ void Copter::init_ardupilot() startup_ground(true); -#if LOGGING_ENABLED == ENABLED - Log_Write_Startup(); -#endif - // we don't want writes to the serial port to cause us to pause // mid-flight, so set the serial ports non-blocking once we are // ready to fly