diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 56c7457364..05d140372a 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -671,13 +671,6 @@ bool ModeAuto::set_speed_down(float speed_down_cms) // start_command - this function will be called when the ap_mission lib wishes to start a new command bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { -#if HAL_LOGGING_ENABLED - // To-Do: logging when new commands start/end - if (copter.should_log(MASK_LOG_CMD)) { - copter.logger.Write_Mission_Cmd(mission, cmd); - } -#endif - switch(cmd.id) { /// diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 620a3bf01c..51982efbed 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -160,6 +160,9 @@ void Copter::init_ardupilot() #if MODE_AUTO_ENABLED // initialise mission library mode_auto.mission.init(); +#if HAL_LOGGING_ENABLED + mode_auto.mission.set_log_start_mission_item_bit(MASK_LOG_CMD); +#endif #endif #if MODE_SMARTRTL_ENABLED