Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

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

Merged
merged 1 commit into from
Mar 8, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading