mirror of https://github.com/ArduPilot/ardupilot
Rover: allow aux switch to record waypoints when not in auto-mode
this reduces the changes required when adding new modes
This commit is contained in:
parent
45d76bdf25
commit
060f1d36dd
|
@ -159,8 +159,8 @@ void Rover::read_aux_switch()
|
|||
return;
|
||||
}
|
||||
|
||||
// record the waypoint if in manual, acro or steering mode
|
||||
if (control_mode == &mode_manual || control_mode == &mode_acro ||control_mode == &mode_steering) {
|
||||
// record the waypoint if not in auto mode
|
||||
if (control_mode != &mode_auto) {
|
||||
// create new mission command
|
||||
AP_Mission::Mission_Command cmd = {};
|
||||
|
||||
|
|
Loading…
Reference in New Issue