Copter: Guided Angle init Z controller on time out

This commit is contained in:
Leonard Hall 2021-07-10 10:55:19 +09:30 committed by Andrew Tridgell
parent 14cfcf18c2
commit 945af08fd0
1 changed files with 5 additions and 1 deletions

View File

@ -833,7 +833,11 @@ void ModeGuided::angle_control_run()
pitch_in = 0.0f;
climb_rate_cms = 0.0f;
yaw_rate_in = 0.0f;
guided_angle_state.use_thrust = false;
if (guided_angle_state.use_thrust) {
// initialise vertical velocity controller
pos_control->init_z_controller();
guided_angle_state.use_thrust = false;
}
}
// interpret positive climb rate or thrust as triggering take-off