mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
APM: Added RST_MISSION_CH option
this allows a pilot to reset the mission using a transmitter switch. Very useful for repeating a mission during testing
This commit is contained in:
parent
e2c8ec2c9e
commit
5498d347f3
@ -70,6 +70,7 @@ public:
|
|||||||
k_param_land_pitch_cd,
|
k_param_land_pitch_cd,
|
||||||
k_param_ins,
|
k_param_ins,
|
||||||
k_param_stick_mixing,
|
k_param_stick_mixing,
|
||||||
|
k_param_reset_mission_chan,
|
||||||
|
|
||||||
// 110: Telemetry control
|
// 110: Telemetry control
|
||||||
//
|
//
|
||||||
@ -289,6 +290,7 @@ public:
|
|||||||
AP_Int16 num_resets;
|
AP_Int16 num_resets;
|
||||||
AP_Int16 log_bitmask;
|
AP_Int16 log_bitmask;
|
||||||
AP_Int8 reset_switch_chan;
|
AP_Int8 reset_switch_chan;
|
||||||
|
AP_Int8 reset_mission_chan;
|
||||||
AP_Int8 manual_level;
|
AP_Int8 manual_level;
|
||||||
AP_Int32 airspeed_cruise_cm;
|
AP_Int32 airspeed_cruise_cm;
|
||||||
AP_Int32 RTL_altitude_cm;
|
AP_Int32 RTL_altitude_cm;
|
||||||
|
@ -379,10 +379,16 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// @Param: RST_SWITCH_CH
|
// @Param: RST_SWITCH_CH
|
||||||
// @DisplayName: Reset Switch Channel
|
// @DisplayName: Reset Switch Channel
|
||||||
// @Description: RC channel to use to reset to last flight mode after geofence takeover
|
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
||||||
|
|
||||||
|
// @Param: RST_MISSION_CH
|
||||||
|
// @DisplayName: Reset Mission Channel
|
||||||
|
// @Description: RC channel to use to reset the mission to the first waypoint. When this channel goes above 1750 the mission is reset. Set RST_MISSION_CH to 0 to disable.
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(reset_mission_chan, "RST_MISSION_CH", 0),
|
||||||
|
|
||||||
// @Param: TRIM_ARSPD_CM
|
// @Param: TRIM_ARSPD_CM
|
||||||
// @DisplayName: Target airspeed
|
// @DisplayName: Target airspeed
|
||||||
// @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode
|
// @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode
|
||||||
|
@ -39,6 +39,13 @@ static void read_control_switch()
|
|||||||
reset_I();
|
reset_I();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (g.reset_mission_chan != 0 &&
|
||||||
|
APM_RC.InputCh(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
|
||||||
|
// reset to first waypoint in mission
|
||||||
|
prev_WP = current_loc;
|
||||||
|
change_command(1);
|
||||||
|
}
|
||||||
|
|
||||||
switch_debouncer = false;
|
switch_debouncer = false;
|
||||||
|
|
||||||
if (g.inverted_flight_ch != 0) {
|
if (g.inverted_flight_ch != 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user