mirror of https://github.com/ArduPilot/ardupilot
ACM: The I term in update_nav_wp with the no_nav condition was pulling from the wrong PID loop and was essentially 0 all the time.
This commit is contained in:
parent
7cf635889d
commit
2ac29effe9
|
@ -2202,8 +2202,8 @@ static void update_nav_wp()
|
||||||
// or change Loiter position
|
// or change Loiter position
|
||||||
|
|
||||||
// We bring copy over our Iterms for wind control, but we don't navigate
|
// We bring copy over our Iterms for wind control, but we don't navigate
|
||||||
nav_lon = g.pi_loiter_lon.get_integrator();
|
nav_lon = g.pid_loiter_rate_lon.get_integrator();
|
||||||
nav_lat = g.pi_loiter_lat.get_integrator();
|
nav_lat = g.pid_loiter_rate_lon.get_integrator();
|
||||||
|
|
||||||
// rotate pitch and roll to the copter frame of reference
|
// rotate pitch and roll to the copter frame of reference
|
||||||
calc_loiter_pitch_roll();
|
calc_loiter_pitch_roll();
|
||||||
|
|
Loading…
Reference in New Issue