mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: fixed position control in QLAND_FINAL
This commit is contained in:
parent
4240d3f739
commit
aab20317a0
@ -1639,13 +1639,14 @@ void QuadPlane::vtol_position_controller(void)
|
||||
// run loiter controller
|
||||
wp_nav->update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
|
||||
plane.nav_pitch_cd,
|
||||
get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds(),
|
||||
smoothing_gain);
|
||||
// nav roll and pitch are controller by position controller
|
||||
plane.nav_roll_cd = pos_control->get_roll();
|
||||
plane.nav_pitch_cd = pos_control->get_pitch();
|
||||
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
|
||||
plane.nav_pitch_cd,
|
||||
get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds(),
|
||||
smoothing_gain);
|
||||
break;
|
||||
|
||||
case QPOS_POSITION1: {
|
||||
|
Loading…
Reference in New Issue
Block a user