Revert "Plane: allow quadplanes to scale ESC CAN like normal"

this change can cause a flyaway if you have low SERVO3_MAX for
k_throttle. This can be reproduced with -f quadplane-can
This commit is contained in:
Andrew Tridgell 2024-03-09 06:21:18 +11:00
parent d24e7a916f
commit eb3215cf12
1 changed files with 10 additions and 3 deletions

View File

@ -49,9 +49,16 @@ void Plane::set_control_channels(void)
quadplane.rc_fwd_thr_ch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
#endif
// setup correct scaling for ESCs like the UAVCAN ESCs which
// take a proportion of speed.
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
bool set_throttle_esc_scaling = true;
#if HAL_QUADPLANE_ENABLED
set_throttle_esc_scaling = !quadplane.enable;
#endif
if (set_throttle_esc_scaling) {
// setup correct scaling for ESCs like the UAVCAN ESCs which
// take a proportion of speed. For quadplanes we use AP_Motors
// scaling
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
}
}
/*