mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: disable ch7/8 feature to point at armed yaw
This commit is contained in:
parent
ba3ba9e157
commit
8e40cbdd7f
@ -276,13 +276,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case AUX_SWITCH_RESETTOARMEDYAW:
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
set_yaw_mode(YAW_RESETTOARMEDYAW);
|
||||
}else{
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
}
|
||||
break;
|
||||
// To-Do: add back support for this feature
|
||||
//case AUX_SWITCH_RESETTOARMEDYAW:
|
||||
// if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
// set_yaw_mode(YAW_RESETTOARMEDYAW);
|
||||
// }else{
|
||||
// set_yaw_mode(YAW_HOLD);
|
||||
// }
|
||||
// break;
|
||||
|
||||
case AUX_SWITCH_ACRO_TRAINER:
|
||||
switch(ch_flag) {
|
||||
|
Loading…
Reference in New Issue
Block a user