mirror of https://github.com/ArduPilot/ardupilot
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:
parent
ec86a30a4d
commit
edc2509ac7
|
@ -216,10 +216,9 @@ void QuadPlane::tailsitter_speed_scaling(void)
|
|||
} else {
|
||||
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_elevator,
|
||||
SRV_Channel::Aux_servo_function_t::k_rudder};
|
||||
SRV_Channel::Aux_servo_function_t::k_elevator};
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(functions); i++) {
|
||||
int32_t v = SRV_Channels::get_output_scaled(functions[i]);
|
||||
v *= scaling;
|
||||
|
|
Loading…
Reference in New Issue