From fd418ca59d0d1e43f987fb099dd34c0945f87b56 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Aug 2024 13:17:22 +1000 Subject: [PATCH] AP_RangeFinder: use GCS_SEND_TEXT rather than gcs().send_text Co-authored-by: muramura --- libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp index 6e7cc156ec..942d0eeb9e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp @@ -104,7 +104,7 @@ void AP_RangeFinder_HC_SR04::update(void) state.distance_m = 0.0f; } } else { - // gcs().send_text(MAV_SEVERITY_WARNING, "Pong!"); + // GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Pong!"); // a new reading - convert time to distance state.distance_m = (value_us * (1.0/58.0f)) * 0.01f; // 58 is from datasheet, mult for performance @@ -134,7 +134,7 @@ void AP_RangeFinder_HC_SR04::update(void) // consider sending new ping if (now - last_ping_ms > 67) { // read ~@15Hz - recommended 60ms delay from datasheet last_ping_ms = now; - // gcs().send_text(MAV_SEVERITY_INFO, "Ping!"); + // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Ping!"); // raise stop pin for n-microseconds hal.gpio->pinMode(trigger_pin, HAL_GPIO_OUTPUT); hal.gpio->write(trigger_pin, 1);