Copter: guided: `set_angle` call `init_z_controller` when changing from thrust to climb rate control to avoid flow of control error

This commit is contained in:
Iampete1 2024-09-15 01:06:42 +01:00 committed by Peter Barker
parent 24df6f1574
commit a4753f32ac
1 changed files with 3 additions and 0 deletions

View File

@ -652,6 +652,9 @@ void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_
// check we are in velocity control mode
if (guided_mode != SubMode::Angle) {
angle_control_start();
} else if (!use_thrust && guided_angle_state.use_thrust) {
// Already angle control but changing from thrust to climb rate
pos_control->init_z_controller();
}
guided_angle_state.attitude_quat = attitude_quat;