Plane: move FBWA_TDRAG_CHAN to RC Options

This commit is contained in:
Iampete1 2021-03-12 21:55:31 +00:00 committed by Andrew Tridgell
parent 77e1092f46
commit 7226a3a9dc
4 changed files with 8 additions and 12 deletions

View File

@ -197,12 +197,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(takeoff_flap_percent, "TKOFF_FLAP_PCNT", 0),
// @Param: FBWA_TDRAG_CHAN
// @DisplayName: FBWA taildragger channel
// @Description: This is a RC input channel which when it goes above 1700 enables FBWA taildragger takeoff mode. It should be assigned to a momentary switch. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA. Setting it to 0 disables this option.
// @User: Standard
GSCALAR(fbwa_tdrag_chan, "FBWA_TDRAG_CHAN", 0),
// @Param: LEVEL_ROLL_LIMIT
// @DisplayName: Level flight roll limit
// @Description: This controls the maximum bank angle in degrees during flight modes where level flight is desired, such as in the final stages of landing, and during auto takeoff. This should be a small angle (such as 5 degrees) to prevent a wing hitting the runway during takeoff or landing. Setting this to zero will completely disable heading hold on auto takeoff and final landing approach.

View File

@ -119,7 +119,7 @@ public:
k_param_glide_slope_min,
k_param_stab_pitch_down,
k_param_terrain_lookahead,
k_param_fbwa_tdrag_chan,
k_param_fbwa_tdrag_chan, // unused - moved to RC option
k_param_rangefinder_landing,
k_param_land_flap_percent, // unused - moved to AP_Landing
k_param_takeoff_flap_percent,
@ -312,7 +312,7 @@ public:
k_param_loiter_radius,
k_param_fence_action,
k_param_fence_total,
k_param_fence_channel,
k_param_fence_channel, // unused - moved to RC option
k_param_fence_minalt,
k_param_fence_maxalt,
@ -476,7 +476,6 @@ public:
#endif
AP_Int16 glide_slope_min;
AP_Float glide_slope_threshold;
AP_Int8 fbwa_tdrag_chan;
AP_Int8 rangefinder_landing;
AP_Int8 flap_slewrate;
#if HAL_WITH_IO_MCU

View File

@ -156,6 +156,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::RTL:
case AUX_FUNC::TAKEOFF:
case AUX_FUNC::FBWA:
case AUX_FUNC::FBWA_TAILDRAGGER:
case AUX_FUNC::FWD_THR:
case AUX_FUNC::LANDING_FLARE:
case AUX_FUNC::PARACHUTE_RELEASE:
@ -246,7 +247,8 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
break;
case AUX_FUNC::FLAP:
break; // flap input label, nothing to do
case AUX_FUNC::FBWA_TAILDRAGGER:
break; // input labels, nothing to do
case AUX_FUNC::Q_ASSIST:
do_aux_function_q_assist_state(ch_flag);

View File

@ -23,9 +23,10 @@ void ModeFBWA::update()
plane.nav_pitch_cd = 0;
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::MIN);
}
if (plane.g.fbwa_tdrag_chan > 0) {
RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FBWA_TAILDRAGGER);
if (chan != nullptr) {
// check for the user enabling FBWA taildrag takeoff mode
bool tdrag_mode = (RC_Channels::get_radio_in(plane.g.fbwa_tdrag_chan-1) > RC_Channel::AUX_PWM_TRIGGER_HIGH);
bool tdrag_mode = chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH;
if (tdrag_mode && !plane.auto_state.fbwa_tdrag_takeoff_mode) {
if (plane.auto_state.highest_airspeed < plane.g.takeoff_tdrag_speed1) {
plane.auto_state.fbwa_tdrag_takeoff_mode = true;