mirror of https://github.com/ArduPilot/ardupilot
Revert "Copter: Remove CH7 & CH8 Enable / Disable of GeoFence"
This reverts commit e25b8933f3
.
This commit is contained in:
parent
7ea971d948
commit
c937fe45e1
|
@ -405,14 +405,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 12:ResetToArmedYaw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 12:ResetToArmedYaw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
|
|
|
@ -86,6 +86,7 @@ static void init_aux_switches()
|
|||
switch(g.ch7_option) {
|
||||
case AUX_SWITCH_SIMPLE_MODE:
|
||||
case AUX_SWITCH_SONAR:
|
||||
case AUX_SWITCH_FENCE:
|
||||
case AUX_SWITCH_RESETTOARMEDYAW:
|
||||
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
|
||||
break;
|
||||
|
@ -100,6 +101,7 @@ static void init_aux_switches()
|
|||
switch(g.ch8_option) {
|
||||
case AUX_SWITCH_SIMPLE_MODE:
|
||||
case AUX_SWITCH_SONAR:
|
||||
case AUX_SWITCH_FENCE:
|
||||
case AUX_SWITCH_RESETTOARMEDYAW:
|
||||
do_aux_switch_function(g.ch8_option, ap_system.CH8_flag);
|
||||
break;
|
||||
|
@ -217,6 +219,12 @@ static void do_aux_switch_function(int8_t ch_function, bool ch_flag)
|
|||
g.sonar_enabled = ch_flag;
|
||||
break;
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
case AUX_SWITCH_FENCE:
|
||||
// enable or disable the fence
|
||||
fence.enable(ch_flag);
|
||||
break;
|
||||
#endif
|
||||
case AUX_SWITCH_RESETTOARMEDYAW:
|
||||
if (ch_flag) {
|
||||
set_yaw_mode(YAW_RESETTOARMEDYAW);
|
||||
|
|
|
@ -60,7 +60,7 @@
|
|||
#define AUX_SWITCH_MULTI_MODE 8 // depending upon CH6 position Flip (if ch6 is low), RTL (if ch6 in middle) or Save WP (if ch6 is high)
|
||||
#define AUX_SWITCH_CAMERA_TRIGGER 9 // trigger camera servo or relay
|
||||
#define AUX_SWITCH_SONAR 10 // allow enabling or disabling sonar in flight which helps avoid surface tracking when you are far above the ground
|
||||
#define AUX_SWITCH_UNUSED_RFU 11 // unused reserved for future use
|
||||
#define AUX_SWITCH_FENCE 11 // allow enabling or disabling fence in flight
|
||||
#define AUX_SWITCH_RESETTOARMEDYAW 12 // changes yaw to be same as when quad was armed
|
||||
|
||||
|
||||
|
@ -185,7 +185,7 @@
|
|||
// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
|
||||
#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
|
||||
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
|
||||
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last
|
||||
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last
|
||||
#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers)
|
||||
|
||||
// TOY mixing options
|
||||
|
|
Loading…
Reference in New Issue