diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 6e97b0a1d2..0e9b0c9423 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -512,13 +512,6 @@ void ModeAuto::send_guided_position_target() /********************************************************************************/ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { -#if HAL_LOGGING_ENABLED - // log when new commands start - if (rover.should_log(MASK_LOG_CMD)) { - rover.logger.Write_Mission_Cmd(mission, cmd); - } -#endif - switch (cmd.id) { case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint return do_nav_wp(cmd, false); diff --git a/Rover/system.cpp b/Rover/system.cpp index 51d9bd079d..6911b78b74 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -125,6 +125,9 @@ void Rover::init_ardupilot() #if AP_MISSION_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 // initialise AP_Logger library