mirror of https://github.com/ArduPilot/ardupilot
Sub: use renamed AC_WPNav::get_yaw_cd and check is active
This commit is contained in:
parent
305f668e12
commit
0f59779bca
|
@ -826,8 +826,7 @@ float ModeGuided::get_auto_heading()
|
||||||
default:
|
default:
|
||||||
// point towards next waypoint.
|
// point towards next waypoint.
|
||||||
// we don't use wp_bearing because we don't want the vehicle to turn too much during flight
|
// we don't use wp_bearing because we don't want the vehicle to turn too much during flight
|
||||||
return sub.wp_nav.get_yaw();
|
return sub.wp_nav.is_active() ? sub.wp_nav.get_yaw_cd() : sub.pos_control.get_yaw_cd();
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// guided_limit_set - set guided timeout and movement limits
|
// guided_limit_set - set guided timeout and movement limits
|
||||||
|
|
Loading…
Reference in New Issue