mirror of https://github.com/ArduPilot/ardupilot
Copter: Guided Angle init Z controller on time out
This commit is contained in:
parent
14cfcf18c2
commit
945af08fd0
|
@ -833,8 +833,12 @@ void ModeGuided::angle_control_run()
|
|||
pitch_in = 0.0f;
|
||||
climb_rate_cms = 0.0f;
|
||||
yaw_rate_in = 0.0f;
|
||||
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
|
||||
const bool positive_thrust_or_climbrate = is_positive(guided_angle_state.use_thrust ? guided_angle_state.thrust : climb_rate_cms);
|
||||
|
|
Loading…
Reference in New Issue