From d69d493ea6f6cf21fc9f89f39561b0505e63448f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Sep 2021 18:56:30 +0100 Subject: [PATCH] AP_TECS: use float for get_throttle_demand --- libraries/AP_TECS/AP_TECS.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 50d5526dc3..2d05bc7d6f 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -56,8 +56,8 @@ public: // demanded throttle in percentage // should return -100 to 100, usually positive unless reverse thrust is enabled via _THRminf < 0 - int32_t get_throttle_demand(void) override { - return int32_t(_throttle_dem * 100.0f); + float get_throttle_demand(void) override { + return _throttle_dem * 100.0f; } // demanded pitch angle in centi-degrees