Copter: emit system time during compassmot on SITL

the autotest framework heavily relies on system_time being emitted -
because we're not running the main loop during compassmot it gets stuck
if we don't do this
This commit is contained in:
Peter Barker 2021-10-16 10:15:13 +11:00 committed by Peter Barker
parent 44359ff6b2
commit d198c3e13d
1 changed files with 4 additions and 0 deletions

View File

@ -228,6 +228,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
#if HAL_WITH_ESC_TELEM
// send ESC telemetry to monitor ESC and motor temperatures
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// a lot of autotest timeouts are based on receiving system time
gcs_chan.send_system_time();
#endif
}
}