Skip to content

Commit

Permalink
Revert "Plane: allow quadplanes to scale ESC CAN like normal"
Browse files Browse the repository at this point in the history
this change can cause a flyaway if you have low SERVO3_MAX for
k_throttle. This can be reproduced with -f quadplane-can
  • Loading branch information
tridge committed Mar 8, 2024
1 parent d24e7a9 commit eb3215c
Showing 1 changed file with 10 additions and 3 deletions.
13 changes: 10 additions & 3 deletions ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

/*
Expand Down

0 comments on commit eb3215c

Please sign in to comment.