Copter: Only run AP_ARMING throttle arming check if PILOT_THR_BHV bit "Feedback from mid stick" is not set

This commit is contained in:
Iampete1 2021-09-18 00:52:34 +01:00 committed by Peter Hall
parent 169375d14f
commit 804efb51e0
2 changed files with 13 additions and 0 deletions

View File

@ -48,6 +48,16 @@ bool RC_Channels_Copter::has_valid_input() const
return true; return true;
} }
// returns true if throttle arming checks should be run
bool RC_Channels_Copter::arming_check_throttle() const {
if ((copter.g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0) {
// center sprung throttle configured, dont run AP_Arming check
// Copter already checks this case in its own arming checks
return false;
}
return RC_Channels::arming_check_throttle();
}
RC_Channel * RC_Channels_Copter::get_arming_channel(void) const RC_Channel * RC_Channels_Copter::get_arming_channel(void) const
{ {
return copter.channel_yaw; return copter.channel_yaw;

View File

@ -42,6 +42,9 @@ public:
return &obj_channels[chan]; return &obj_channels[chan];
} }
// returns true if throttle arming checks should be run
bool arming_check_throttle() const override;
protected: protected:
int8_t flight_mode_channel_number() const override; int8_t flight_mode_channel_number() const override;