mirror of https://github.com/ArduPilot/ardupilot
Plane: allow quadplanes to scale ESC CAN like normal
This commit is contained in:
parent
171da3dd08
commit
155f31a3a2
|
@ -49,16 +49,9 @@ void Plane::set_control_channels(void)
|
|||
quadplane.rc_fwd_thr_ch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
|
||||
#endif
|
||||
|
||||
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);
|
||||
}
|
||||
// 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);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue