mirror of https://github.com/ArduPilot/ardupilot
Plane: quadplane: set `last_pidz_init_ms`
This commit is contained in:
parent
723b1f86ed
commit
dc869860e7
|
@ -1092,6 +1092,7 @@ void QuadPlane::run_z_controller(void)
|
|||
// initialise the vertical position controller with no descent
|
||||
pos_control->init_z_controller_no_descent();
|
||||
}
|
||||
last_pidz_init_ms = now;
|
||||
}
|
||||
last_pidz_active_ms = now;
|
||||
pos_control->update_z_controller();
|
||||
|
|
Loading…
Reference in New Issue