Plane: Assign flap channel in set_control_channels() to avoid expensive call in set_servos_flaps().

This commit is contained in:
Samuel Tabor 2020-09-02 09:31:38 +01:00 committed by Andrew Tridgell
parent 590ebb180c
commit 93bcfc4c3e
3 changed files with 5 additions and 4 deletions

View File

@ -177,6 +177,7 @@ private:
RC_Channel *channel_pitch;
RC_Channel *channel_throttle;
RC_Channel *channel_rudder;
RC_Channel *channel_flap;
RC_Channel *channel_airbrake;
AP_Logger logger;

View File

@ -40,7 +40,8 @@ void Plane::set_control_channels(void)
SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100);
}
// update airbrake channel assignment
// update flap and airbrake channel assignment
channel_flap = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FLAP);
channel_airbrake = rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRBRAKE);
// update manual forward throttle channel assignment

View File

@ -584,9 +584,8 @@ void Plane::set_servos_flaps(void)
int8_t manual_flap_percent = 0;
// work out any manual flap input
RC_Channel *flapin = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FLAP);
if (flapin != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) {
manual_flap_percent = flapin->percent_input();
if (channel_flap != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) {
manual_flap_percent = channel_flap->percent_input();
}
if (auto_throttle_mode) {