RC_Channel: handle AUX_FUNC::ARMDISARM

This commit is contained in:
Peter Barker 2019-05-03 21:26:28 +10:00 committed by Randy Mackay
parent b857d2c1af
commit c38e5ba4fc
1 changed files with 16 additions and 0 deletions

View File

@ -35,6 +35,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_Gripper/AP_Gripper.h>
#include <AP_LandingGear/AP_LandingGear.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Arming/AP_Arming.h>
const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Param: MIN
@ -679,6 +680,21 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
do_aux_function_lost_vehicle_sound(ch_flag);
break;
case AUX_FUNC::ARMDISARM:
// arm or disarm the vehicle
switch (ch_flag) {
case HIGH:
AP::arming().arm(AP_Arming::Method::AUXSWITCH, true);
break;
case MIDDLE:
// nothing
break;
case LOW:
AP::arming().disarm();
break;
}
break;
case AUX_FUNC::COMPASS_LEARN:
if (ch_flag == HIGH) {
Compass &compass = AP::compass();