Plane: quadplane: set `last_pidz_init_ms`

This commit is contained in:
Peter Hall 2021-08-28 14:50:19 +01:00 committed by Randy Mackay
parent 723b1f86ed
commit dc869860e7
1 changed files with 1 additions and 0 deletions

View File

@ -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();