AP_TECS: use float for get_throttle_demand

This commit is contained in:
Iampete1 2021-09-18 18:56:30 +01:00 committed by Andrew Tridgell
parent fbb9ef422c
commit d69d493ea6
1 changed files with 2 additions and 2 deletions

View File

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