Plane: make throttle_percentage() signed

This commit is contained in:
Tom Pittenger 2016-02-08 21:46:56 -08:00 committed by Andrew Tridgell
parent a7079b730a
commit fa53263ca9
2 changed files with 7 additions and 2 deletions

View File

@ -1194,7 +1194,7 @@ void Plane::demo_servos(uint8_t i)
void Plane::adjust_nav_pitch_throttle(void)
{
int8_t throttle = throttle_percentage();
if (throttle < aparm.throttle_cruise && flight_stage != AP_SpdHgtControl::FLIGHT_VTOL) {
if (throttle >= 0 && throttle < aparm.throttle_cruise && flight_stage != AP_SpdHgtControl::FLIGHT_VTOL) {
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
}

View File

@ -765,7 +765,12 @@ int8_t Plane::throttle_percentage(void)
}
// to get the real throttle we need to use norm_output() which
// returns a number from -1 to 1.
return constrain_int16(50*(channel_throttle->norm_output()+1), 0, 100);
if (aparm.throttle_min >= 0) {
return constrain_int16(50*(channel_throttle->norm_output()+1), 0, 100);
} else {
// reverse thrust
return constrain_int16(100*channel_throttle->norm_output(), -100, 100);
}
}
/*