mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
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:
parent
24df6f1574
commit
a4753f32ac
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user