AP_RangeFinder: use GCS_SEND_TEXT()

This commit is contained in:
Andrew Tridgell 2020-03-30 09:49:53 +11:00
parent 9350c78023
commit b102fd6b59
1 changed files with 2 additions and 2 deletions

View File

@ -80,7 +80,7 @@ void AP_RangeFinder_PWM::check_pin()
// detach last one // detach last one
if (last_pin > 0) { if (last_pin > 0) {
if (!hal.gpio->detach_interrupt(last_pin)) { if (!hal.gpio->detach_interrupt(last_pin)) {
gcs().send_text(MAV_SEVERITY_WARNING, GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"RangeFinder_PWM: Failed to detach from pin %u", "RangeFinder_PWM: Failed to detach from pin %u",
last_pin); last_pin);
// ignore this failure or the user may be stuck // ignore this failure or the user may be stuck
@ -107,7 +107,7 @@ void AP_RangeFinder_PWM::check_pin()
uint32_t), uint32_t),
AP_HAL::GPIO::INTERRUPT_BOTH)) { AP_HAL::GPIO::INTERRUPT_BOTH)) {
// failed to attach interrupt // failed to attach interrupt
gcs().send_text(MAV_SEVERITY_WARNING, GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
"RangeFinder_PWM: Failed to attach to pin %u", "RangeFinder_PWM: Failed to attach to pin %u",
(unsigned int)params.pin); (unsigned int)params.pin);
return; return;