From a8e2923774371d287a0b64ad2db34c42c49470a8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 3 Dec 2019 23:55:58 +1100 Subject: [PATCH] Tracker: correct scan mode pitch clamping --- AntennaTracker/mode.cpp | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/AntennaTracker/mode.cpp b/AntennaTracker/mode.cpp index 9c60867340..a79bf53481 100644 --- a/AntennaTracker/mode.cpp +++ b/AntennaTracker/mode.cpp @@ -45,15 +45,19 @@ void Mode::update_scan(void) } if (!nav_status.manual_control_pitch) { - float pitch_delta = g.scan_speed_pitch * 0.02f; - nav_status.pitch += pitch_delta * (nav_status.scan_reverse_pitch?-1:1); - if (nav_status.pitch < g.pitch_min && nav_status.scan_reverse_pitch) { - nav_status.scan_reverse_pitch = false; + const float pitch_delta = g.scan_speed_pitch * 0.02f; + if (nav_status.scan_reverse_pitch) { + nav_status.pitch -= pitch_delta; + if (nav_status.pitch < g.pitch_min) { + nav_status.scan_reverse_pitch = false; + } + } else { + nav_status.pitch += pitch_delta; + if (nav_status.pitch > g.pitch_max) { + nav_status.scan_reverse_pitch = true; + } } - if (nav_status.pitch > g.pitch_max && !nav_status.scan_reverse_pitch) { - nav_status.scan_reverse_pitch = true; - } - nav_status.pitch = constrain_float(nav_status.pitch, -g.pitch_min, g.pitch_max); + nav_status.pitch = constrain_float(nav_status.pitch, g.pitch_min, g.pitch_max); } update_auto();