AR_Motors: use GCS_SEND_TEXT rather than gcs().send_text

Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
Peter Barker 2024-08-07 13:17:22 +10:00 committed by Andrew Tridgell
parent 7c1d37f374
commit c0b905f6e6
1 changed files with 1 additions and 1 deletions

View File

@ -546,7 +546,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const
for (uint8_t i=0; i<ARRAY_SIZE(relay_table); i++) {
if (relay_table[i].output_assigned && !relay->enabled(relay_table[i].fun)) {
if (report) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: relay function %u unassigned", uint8_t(relay_table[i].fun));
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: relay function %u unassigned", uint8_t(relay_table[i].fun));
}
return false;
}