ArduCopter: adjust for AP_Mission logging mission-item-starts

This commit is contained in:
Peter Barker 2024-09-27 17:37:58 +10:00 committed by Andrew Tridgell
parent 163f49827f
commit 9f1690ac20
2 changed files with 3 additions and 7 deletions

View File

@ -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 // 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) 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) { switch(cmd.id) {
/// ///

View File

@ -160,6 +160,9 @@ void Copter::init_ardupilot()
#if MODE_AUTO_ENABLED #if MODE_AUTO_ENABLED
// initialise mission library // initialise mission library
mode_auto.mission.init(); mode_auto.mission.init();
#if HAL_LOGGING_ENABLED
mode_auto.mission.set_log_start_mission_item_bit(MASK_LOG_CMD);
#endif
#endif #endif
#if MODE_SMARTRTL_ENABLED #if MODE_SMARTRTL_ENABLED