From b4a779aec367186431fc6f13dcccb05aebded1bc Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Dec 2017 12:15:50 +0900 Subject: [PATCH] Rover: add arm/disarm to ch7 switch --- APMrover2/Parameters.cpp | 2 +- APMrover2/control_modes.cpp | 9 +++++++++ APMrover2/defines.h | 3 ++- 3 files changed, 12 insertions(+), 2 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 8f366d3c04..517a0ec97d 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -129,7 +129,7 @@ const AP_Param::Info Rover::var_info[] = { // @Param: CH7_OPTION // @DisplayName: Channel 7 option // @Description: What to do use channel 7 for - // @Values: 0:Nothing,1:SaveWaypoint,2:LearnCruiseSpeed + // @Values: 0:Nothing,1:SaveWaypoint,2:LearnCruiseSpeed,3:ArmDisarm // @User: Standard GSCALAR(ch7_option, "CH7_OPTION", CH7_OPTION), diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index ba87692909..9fcf8cd208 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -189,6 +189,15 @@ void Rover::read_aux_switch() cruise_learn_complete(); } break; + + // arm or disarm the motors + case CH7_ARM_DISARM: + if (aux_ch7 == AUX_SWITCH_HIGH) { + arm_motors(AP_Arming::RUDDER); + } else if (aux_ch7 == AUX_SWITCH_LOW) { + disarm_motors(); + } + break; } } diff --git a/APMrover2/defines.h b/APMrover2/defines.h index 3a5c109519..3314a1042c 100644 --- a/APMrover2/defines.h +++ b/APMrover2/defines.h @@ -17,7 +17,8 @@ enum ch7_option { CH7_DO_NOTHING = 0, CH7_SAVE_WP = 1, - CH7_LEARN_CRUISE = 2 + CH7_LEARN_CRUISE = 2, + CH7_ARM_DISARM = 3 }; // HIL enumerations