mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Plane: Assign flap channel in set_control_channels() to avoid expensive call in set_servos_flaps().
This commit is contained in:
parent
590ebb180c
commit
93bcfc4c3e
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user