Plane: move RST_MISSION_CH to RC option
This commit is contained in:
parent
ebe841ba70
commit
eeab196d91
@ -650,12 +650,6 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @User: Advanced
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
||||
|
||||
// @Param: RST_MISSION_CH
|
||||
// @DisplayName: Reset Mission Channel
|
||||
// @Description: Enables a channel to reset the mission to the first waypoint. Mission restart is triggered by channel rising above 1750 PWM. 0 disables.
|
||||
// @User: Advanced
|
||||
GSCALAR(reset_mission_chan, "RST_MISSION_CH", 0),
|
||||
|
||||
// @Param: TRIM_ARSPD_CM
|
||||
// @DisplayName: Target airspeed
|
||||
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
|
||||
|
@ -67,7 +67,7 @@ public:
|
||||
k_param_land_pitch_cd, // unused - moved to AP_Landing
|
||||
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
||||
k_param_stick_mixing,
|
||||
k_param_reset_mission_chan,
|
||||
k_param_reset_mission_chan, // unused - moved to RC option
|
||||
k_param_land_flare_alt, // unused - moved to AP_Landing
|
||||
k_param_land_flare_sec, // unused - moved to AP_Landing
|
||||
k_param_crosstrack_min_distance, // unused
|
||||
@ -447,7 +447,6 @@ public:
|
||||
AP_Int16 num_resets;
|
||||
AP_Int32 log_bitmask;
|
||||
AP_Int8 reset_switch_chan;
|
||||
AP_Int8 reset_mission_chan;
|
||||
AP_Int32 RTL_altitude_cm;
|
||||
AP_Int16 pitch_trim_cd;
|
||||
AP_Int16 FBWB_min_altitude_cm;
|
||||
|
@ -135,6 +135,12 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
|
||||
}
|
||||
}
|
||||
|
||||
void RC_Channel_Plane::do_aux_function_mission_reset(const AuxSwitchPos ch_flag)
|
||||
{
|
||||
plane.mission.start();
|
||||
plane.prev_WP_loc = plane.current_loc;
|
||||
}
|
||||
|
||||
void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
||||
const RC_Channel::AuxSwitchPos ch_flag)
|
||||
{
|
||||
|
@ -26,6 +26,8 @@ private:
|
||||
|
||||
void do_aux_function_flare(AuxSwitchPos ch_flag);
|
||||
|
||||
void do_aux_function_mission_reset(const AuxSwitchPos ch_flag) override;
|
||||
|
||||
};
|
||||
|
||||
class RC_Channels_Plane : public RC_Channels
|
||||
|
@ -129,12 +129,6 @@ void Plane::read_control_switch()
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
|
||||
if (g.reset_mission_chan != 0 &&
|
||||
RC_Channels::get_radio_in(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
|
||||
mission.start();
|
||||
prev_WP_loc = current_loc;
|
||||
}
|
||||
|
||||
switch_debouncer = false;
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user