mirror of https://github.com/ArduPilot/ardupilot
Copter: AUTO and Guided call wp_and_spline_init
This commit is contained in:
parent
11918869a5
commit
3cc5b9446f
|
@ -26,6 +26,10 @@ static bool auto_init(bool ignore_checks)
|
|||
if (auto_yaw_mode == AUTO_YAW_ROI) {
|
||||
set_auto_yaw_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
|
||||
// initialise waypoint and spline controller
|
||||
wp_nav.wp_and_spline_init();
|
||||
|
||||
// start the mission
|
||||
mission.start();
|
||||
return true;
|
||||
|
|
|
@ -14,6 +14,10 @@ static bool guided_pilot_yaw_override_yaw = false;
|
|||
static bool guided_init(bool ignore_checks)
|
||||
{
|
||||
if (GPS_ok() || ignore_checks) {
|
||||
|
||||
// initialise waypoint and spline controller
|
||||
wp_nav.wp_and_spline_init();
|
||||
|
||||
// initialise wpnav to stopping point at current altitude
|
||||
// To-Do: set to current location if disarmed?
|
||||
// To-Do: set to stopping point altitude?
|
||||
|
|
Loading…
Reference in New Issue