Sub: Don't emit tether turn status via STATUSTEXT

We have NAMED_VALUE_FLOAT do that now
This commit is contained in:
Jacob Walser 2017-10-20 14:40:16 -04:00
parent 8178ab4037
commit 7bed518181
1 changed files with 0 additions and 8 deletions

View File

@ -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;
}