From 9767c743112dfd13894b83ac7cfde7762e721016 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Wed, 5 Dec 2018 21:07:12 +0900
Subject: [PATCH] AP_Mount: angle_input uses norm_input

---
 libraries/AP_Mount/AP_Mount_Backend.cpp | 4 +---
 1 file changed, 1 insertion(+), 3 deletions(-)

diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp
index 5fb3e4a1eb..1b5913b6d8 100644
--- a/libraries/AP_Mount/AP_Mount_Backend.cpp
+++ b/libraries/AP_Mount/AP_Mount_Backend.cpp
@@ -125,9 +125,7 @@ void AP_Mount_Backend::update_targets_from_rc()
 // returns the angle (degrees*100) that the RC_Channel input is receiving
 int32_t AP_Mount_Backend::angle_input(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
 {
-    int16_t radio_in = constrain_int16(rc->get_radio_in(),  rc->get_radio_min(),  rc->get_radio_max());
-    return (rc->get_reverse() ? -1 : 1) * (radio_in - rc->get_radio_min())
-      * (int32_t)(angle_max - angle_min) / (rc->get_radio_max() - rc->get_radio_min()) + (rc->get_reverse() ? angle_max : angle_min);
+    return (rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min;
 }
 
 // returns the angle (radians) that the RC_Channel input is receiving