From 0d0ff632420847e4328ce29739afd7c13c43e4e5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 7 Oct 2020 11:19:31 +0900 Subject: [PATCH] Plane: ensure wp_nav::wp_and_spline_init is called at least once --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index b3654e4398..e87485a822 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -774,12 +774,12 @@ bool QuadPlane::setup(void) motors->disable_yaw_torque(); } - motors->set_throttle_range(thr_min_pwm, thr_max_pwm); motors->set_update_rate(rc_speed); motors->set_interlock(true); pos_control->set_dt(loop_delta_t); attitude_control->parameter_sanity_check(); + wp_nav->wp_and_spline_init(); // TODO: update this if servo function assignments change // used by relax_attitude_control() to control special behavior for vectored tailsitters