From 7bed518181103ca44574ba2c3eeb870aae536319 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Fri, 20 Oct 2017 14:40:16 -0400 Subject: [PATCH] Sub: Don't emit tether turn status via STATUSTEXT We have NAMED_VALUE_FLOAT do that now --- ArduSub/turn_counter.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ArduSub/turn_counter.cpp b/ArduSub/turn_counter.cpp index dc20fe517f..f2260aa12e 100644 --- a/ArduSub/turn_counter.cpp +++ b/ArduSub/turn_counter.cpp @@ -53,13 +53,5 @@ void Sub::update_turn_counter() } break; } - static int32_t last_turn_count_printed; - static uint32_t last_turn_announce_ms = 0; - uint32_t tnow = AP_HAL::millis(); - if (quarter_turn_count/4 != last_turn_count_printed && tnow > last_turn_announce_ms + 2000) { - last_turn_announce_ms = tnow; - gcs().send_text(MAV_SEVERITY_INFO,"Tether is turned %i turns %s",int32_t(abs(quarter_turn_count)/4),(quarter_turn_count>0)?"to the right":"to the left"); - last_turn_count_printed = quarter_turn_count/4; - } last_turn_state = turn_state; }