mirror of https://github.com/ArduPilot/ardupilot
Rover: fix set_target_location to always use Guided mode
Without this fix, if lua sent a target location while in Guided-within-Auto the Auto submode would be changed out of Guided-within-Auto meaning follow-up commands from lua or a companion computer would be ignored
This commit is contained in:
parent
bf8ce85b4d
commit
8a7a22e707
|
@ -165,7 +165,7 @@ bool Rover::set_target_location(const Location& target_loc)
|
|||
return false;
|
||||
}
|
||||
|
||||
return control_mode->set_desired_location(target_loc);
|
||||
return mode_guided.set_desired_location(target_loc);
|
||||
}
|
||||
|
||||
// set target velocity (for use by scripting)
|
||||
|
|
Loading…
Reference in New Issue