From 2d161e35941fb8b25c00c6845b99d020ed289745 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 4 Apr 2019 03:50:00 -0700 Subject: [PATCH] AP_Mount: Remove unneeded headers --- libraries/AP_Mount/AP_Mount.h | 5 +---- libraries/AP_Mount/AP_Mount_Backend.cpp | 9 ++------- libraries/AP_Mount/AP_Mount_Backend.h | 4 ++-- 3 files changed, 5 insertions(+), 13 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 46ac4cc559..a22c57ec1c 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -21,12 +21,9 @@ #include #include -#include -#include +#include #include -#include #include -#include // maximum number of mounts #define AP_MOUNT_MAX_INSTANCES 1 diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 574cf862ed..bb28b1c387 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -1,4 +1,5 @@ #include "AP_Mount_Backend.h" +#include extern const AP_HAL::HAL& hal; @@ -124,16 +125,10 @@ 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) -{ - 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 float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max) { - return radians(angle_input(rc, angle_min, angle_max)*0.01f); + return radians(((rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f); } // calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index ed77ffebfb..7e41e8b3eb 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -21,6 +21,7 @@ #include #include "AP_Mount.h" +#include class AP_Mount_Backend { @@ -82,8 +83,7 @@ protected: // update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver void update_targets_from_rc(); - // angle_input, angle_input_rad - convert RC input into an earth-frame target angle - int32_t angle_input(const RC_Channel* rc, int16_t angle_min, int16_t angle_max); + // angle_input_rad - convert RC input into an earth-frame target angle float angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max); // calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target