From 590ebb180caacccd4d505bfc9b4d543093222fbd Mon Sep 17 00:00:00 2001 From: Samuel Tabor Date: Wed, 2 Sep 2020 08:33:02 +0100 Subject: [PATCH] Plane: Update airbrake channel assignment in set_control_channels() to avoid expensive call in airbrake_update() --- ArduPlane/Plane.h | 1 + ArduPlane/radio.cpp | 3 +++ ArduPlane/servos.cpp | 8 +++----- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3dd8ec2fbf..2d8f4f22fc 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -177,6 +177,7 @@ private: RC_Channel *channel_pitch; RC_Channel *channel_throttle; RC_Channel *channel_rudder; + RC_Channel *channel_airbrake; AP_Logger logger; diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 6e710f82ed..93fcfb240c 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -40,6 +40,9 @@ void Plane::set_control_channels(void) SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100); } + // update airbrake channel assignment + channel_airbrake = rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRBRAKE); + // update manual forward throttle channel assignment quadplane.rc_fwd_thr_ch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index f1996e7042..7ec577a950 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -296,11 +296,9 @@ void Plane::airbrake_update(void) { // Calculate any manual airbrake input from RC channel option. int8_t manual_airbrake_percent = 0; - - RC_Channel *airbrake_in_ch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRBRAKE); - - if (airbrake_in_ch != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) { - manual_airbrake_percent = airbrake_in_ch->percent_input(); + + if (channel_airbrake != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) { + manual_airbrake_percent = channel_airbrake->percent_input(); } // Calculate auto airbrake from negative throttle.