mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: guided removes xy mode in calls to pos-con
Also limit angle to hold altitude
This commit is contained in:
parent
1a0be015f9
commit
f9acc8a666
@ -553,7 +553,7 @@ void Copter::ModeGuided::posvel_control_run()
|
||||
pos_control->set_desired_velocity_xy(guided_vel_target_cms.x, guided_vel_target_cms.y);
|
||||
|
||||
// run position controller
|
||||
pos_control->update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler, false);
|
||||
pos_control->update_xy_controller(ekfNavVelGainScaler);
|
||||
}
|
||||
|
||||
pos_control->update_z_controller();
|
||||
|
Loading…
Reference in New Issue
Block a user