mirror of https://github.com/ArduPilot/ardupilot
Plane: Update airbrake channel assignment in set_control_channels() to avoid expensive call in airbrake_update()
This commit is contained in:
parent
f1290a2e17
commit
590ebb180c
|
@ -177,6 +177,7 @@ private:
|
|||
RC_Channel *channel_pitch;
|
||||
RC_Channel *channel_throttle;
|
||||
RC_Channel *channel_rudder;
|
||||
RC_Channel *channel_airbrake;
|
||||
|
||||
AP_Logger logger;
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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.
|
||||
|
|
Loading…
Reference in New Issue