mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
ArduCopter:mode_guided: yaw initialization already in pos_control_start()
This commit is contained in:
parent
840362f355
commit
57598e5b9f
@ -39,8 +39,6 @@ struct Guided_Limit {
|
||||
bool Copter::ModeGuided::init(bool ignore_checks)
|
||||
{
|
||||
if (copter.position_ok() || ignore_checks) {
|
||||
// initialise yaw
|
||||
auto_yaw.set_mode_to_default(false);
|
||||
// start in position control mode
|
||||
pos_control_start();
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user