Plane: quadplane: forward throttle reutrn float

This commit is contained in:
Iampete1 2021-09-18 19:05:54 +01:00 committed by Andrew Tridgell
parent 2f93c1f9e4
commit 73e9c9bb43
2 changed files with 4 additions and 4 deletions

View File

@ -3081,7 +3081,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
reduces the need for down pitch which reduces load on the vertical reduces the need for down pitch which reduces load on the vertical
lift motors. lift motors.
*/ */
int8_t QuadPlane::forward_throttle_pct() float QuadPlane::forward_throttle_pct()
{ {
/* /*
Unless an RC channel is assigned for manual forward throttle control, Unless an RC channel is assigned for manual forward throttle control,
@ -3191,7 +3191,7 @@ int8_t QuadPlane::forward_throttle_pct()
vel_forward.last_pct = linear_interpolate(0, vel_forward.integrator, vel_forward.last_pct = linear_interpolate(0, vel_forward.integrator,
height_above_ground, alt_cutoff, alt_cutoff+2); height_above_ground, alt_cutoff, alt_cutoff+2);
} }
if (vel_forward.last_pct == 0) { if (is_zero(vel_forward.last_pct)) {
// if the percent is 0 then decay the integrator // if the percent is 0 then decay the integrator
vel_forward.integrator *= 0.95f; vel_forward.integrator *= 0.95f;
} }

View File

@ -117,7 +117,7 @@ public:
} }
// return desired forward throttle percentage // return desired forward throttle percentage
int8_t forward_throttle_pct(); float forward_throttle_pct();
float get_weathervane_yaw_rate_cds(void); float get_weathervane_yaw_rate_cds(void);
// see if we are flying from vtol point of view // see if we are flying from vtol point of view
@ -356,7 +356,7 @@ private:
AP_Float gain; AP_Float gain;
float integrator; float integrator;
uint32_t last_ms; uint32_t last_ms;
int8_t last_pct; float last_pct;
} vel_forward; } vel_forward;
struct { struct {