From 5b69ff6e659b867b0ffbc35ac60348cd62f8c552 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 16 Oct 2021 11:09:35 +1100 Subject: [PATCH] Copter: send RC_CHANNELS in SITL in compassmot loop When setting an RC value in autotest, we require the change to appear in this message --- ArduCopter/compassmot.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 8f00d6f5e7..703f5cf722 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -232,6 +232,8 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // a lot of autotest timeouts are based on receiving system time gcs_chan.send_system_time(); + // autotesting of compassmot wants to see RC channels message + gcs_chan.send_rc_channels(); #endif } }