mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_RangeFinder: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
cee45a2fc2
commit
fd418ca59d
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user