Skip to content

Commit 438ab2b

Browse files
committed
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
1 parent 0f0023e commit 438ab2b

File tree

1 file changed

+4
-0
lines changed

1 file changed

+4
-0
lines changed

ArduCopter/compassmot.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -228,6 +228,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
228228
#if HAL_WITH_ESC_TELEM
229229
// send ESC telemetry to monitor ESC and motor temperatures
230230
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
231+
#endif
232+
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
233+
// a lot of autotest timeouts are based on receiving system time
234+
gcs_chan.send_system_time();
231235
#endif
232236
}
233237
}

0 commit comments

Comments
 (0)