Plane: disable rudder scaling in tailsitters

this is most often implemented as dual-motor differential thrust, and
we don't want to do surface speed scaling for that.

In the future we'll move this scaling so it can be done on rudders for
3D planes
This commit is contained in:
Andrew Tridgell 2017-11-13 14:58:40 +11:00
parent a18cf45798
commit e06f160dc9

View File

@ -216,10 +216,9 @@ void QuadPlane::tailsitter_speed_scaling(void)
} else { } else {
scaling = constrain_float(hover_throttle / throttle, 1/scaling_max, scaling_max); scaling = constrain_float(hover_throttle / throttle, 1/scaling_max, scaling_max);
} }
const SRV_Channel::Aux_servo_function_t functions[3] = { const SRV_Channel::Aux_servo_function_t functions[2] = {
SRV_Channel::Aux_servo_function_t::k_aileron, SRV_Channel::Aux_servo_function_t::k_aileron,
SRV_Channel::Aux_servo_function_t::k_elevator, SRV_Channel::Aux_servo_function_t::k_elevator};
SRV_Channel::Aux_servo_function_t::k_rudder};
for (uint8_t i=0; i<ARRAY_SIZE(functions); i++) { for (uint8_t i=0; i<ARRAY_SIZE(functions); i++) {
int32_t v = SRV_Channels::get_output_scaled(functions[i]); int32_t v = SRV_Channels::get_output_scaled(functions[i]);
v *= scaling; v *= scaling;