mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: use GCS_SEND_TEXT()
This commit is contained in:
parent
9350c78023
commit
b102fd6b59
@ -80,7 +80,7 @@ void AP_RangeFinder_PWM::check_pin()
|
||||
// detach last one
|
||||
if (last_pin > 0) {
|
||||
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",
|
||||
last_pin);
|
||||
// ignore this failure or the user may be stuck
|
||||
@ -107,7 +107,7 @@ void AP_RangeFinder_PWM::check_pin()
|
||||
uint32_t),
|
||||
AP_HAL::GPIO::INTERRUPT_BOTH)) {
|
||||
// failed to attach interrupt
|
||||
gcs().send_text(MAV_SEVERITY_WARNING,
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,
|
||||
"RangeFinder_PWM: Failed to attach to pin %u",
|
||||
(unsigned int)params.pin);
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user