mirror of https://github.com/ArduPilot/ardupilot
Copter: accept guided pos updates when doing NAV_GUIDED cmd
This commit is contained in:
parent
fdc0ec837b
commit
279926e386
|
@ -857,7 +857,7 @@ static bool verify_yaw()
|
||||||
static bool do_guided(const AP_Mission::Mission_Command& cmd)
|
static bool do_guided(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
// only process guided waypoint if we are in guided mode
|
// only process guided waypoint if we are in guided mode
|
||||||
if (control_mode != GUIDED) {
|
if (control_mode != GUIDED && !(control_mode == AUTO && auto_mode == Auto_NavGuided)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue