mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
ffb2a32144
commit
fa4e90a3bb
@ -1561,7 +1561,7 @@ void Compass::probe_dronecan_compasses(void)
|
||||
}
|
||||
// We have found a replacement mag, let's replace the existing one
|
||||
// with this by setting the priority to zero and calling uavcan probe
|
||||
gcs().send_text(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu replaced", uint8_t(i), (unsigned long)_priority_did_list[i]);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu replaced", uint8_t(i), (unsigned long)_priority_did_list[i]);
|
||||
_priority_did_stored_list[i].set_and_save(0);
|
||||
_priority_did_list[i] = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user