mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: guided_posvel run update_z_controller at 400hz
This commit is contained in:
parent
da629ce976
commit
36cc832931
@ -331,9 +331,10 @@ static void guided_posvel_control_run()
|
||||
|
||||
// run position controller
|
||||
pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler);
|
||||
pos_control.update_z_controller();
|
||||
}
|
||||
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// call attitude controller
|
||||
if (auto_yaw_mode == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
|
Loading…
Reference in New Issue
Block a user