mirror of https://github.com/ArduPilot/ardupilot
Rover: allow mode to be set from ch7 switch
This commit is contained in:
parent
ed558dd9a0
commit
0c6afac5c6
|
@ -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,3:ArmDisarm
|
||||
// @Values: 0:Nothing,1:SaveWaypoint,2:LearnCruiseSpeed,3:ArmDisarm,4:Manual,5:Acro,6:Steering,7:Hold,8:Auto,9:RTL,10:SmartRTL,11:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPTION", CH7_OPTION),
|
||||
|
||||
|
|
|
@ -198,6 +198,78 @@ void Rover::read_aux_switch()
|
|||
disarm_motors();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Manual
|
||||
case CH7_MANUAL:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_manual, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_manual)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Acro
|
||||
case CH7_ACRO:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_acro, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_acro)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Steering
|
||||
case CH7_STEERING:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_steering, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_steering)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Hold
|
||||
case CH7_HOLD:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_hold, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_hold)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Auto
|
||||
case CH7_AUTO:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_auto, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_auto)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to RTL
|
||||
case CH7_RTL:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_rtl, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_rtl)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to SmartRTL
|
||||
case CH7_SMART_RTL:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_smartrtl, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_smartrtl)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
|
||||
// set mode to Guided
|
||||
case CH7_GUIDED:
|
||||
if (aux_ch7 == AUX_SWITCH_HIGH) {
|
||||
set_mode(mode_guided, MODE_REASON_TX_COMMAND);
|
||||
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_guided)) {
|
||||
reset_control_switch();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -18,7 +18,15 @@ enum ch7_option {
|
|||
CH7_DO_NOTHING = 0,
|
||||
CH7_SAVE_WP = 1,
|
||||
CH7_LEARN_CRUISE = 2,
|
||||
CH7_ARM_DISARM = 3
|
||||
CH7_ARM_DISARM = 3,
|
||||
CH7_MANUAL = 4,
|
||||
CH7_ACRO = 5,
|
||||
CH7_STEERING = 6,
|
||||
CH7_HOLD = 7,
|
||||
CH7_AUTO = 8,
|
||||
CH7_RTL = 9,
|
||||
CH7_SMART_RTL = 10,
|
||||
CH7_GUIDED = 11
|
||||
};
|
||||
|
||||
// HIL enumerations
|
||||
|
|
Loading…
Reference in New Issue