Copter: guided mode vel controller integrates althold lean limit
Note it does not yet actually limit the lean angles based on throttle
This commit is contained in:
parent
543f6fdcd4
commit
0eaf815411
@ -363,7 +363,7 @@ void Copter::guided_posvel_control_run()
|
||||
pos_control.set_desired_velocity_xy(posvel_vel_target_cms.x, posvel_vel_target_cms.y);
|
||||
|
||||
// run position controller
|
||||
pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler);
|
||||
pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler, false);
|
||||
}
|
||||
|
||||
pos_control.update_z_controller();
|
||||
|
Loading…
Reference in New Issue
Block a user