Copter: default Ch7 to DO_NOTHING

Ch7/Ch8 Save_WP feature triggers when switch is brought high (instead of
low) to be consistent with other aux features
This commit is contained in:
Randy Mackay 2013-11-01 11:42:33 +09:00
parent 97770ae352
commit babc54ec60
2 changed files with 3 additions and 3 deletions

View File

@ -286,7 +286,7 @@
//
#ifndef CH7_OPTION
# define CH7_OPTION AUX_SWITCH_SAVE_WP
# define CH7_OPTION AUX_SWITCH_DO_NOTHING
#endif
#ifndef CH8_OPTION

View File

@ -178,8 +178,8 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break;
case AUX_SWITCH_SAVE_WP:
// save waypoint when switch is switched off
if (ch_flag == AUX_SWITCH_LOW) {
// save waypoint when switch is brought high
if (ch_flag == AUX_SWITCH_HIGH) {
// if in auto mode, reset the mission
if(control_mode == AUTO) {