mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: ensure wp_nav::wp_and_spline_init is called at least once
This commit is contained in:
parent
031be010ac
commit
0d0ff63242
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user