mirror of https://github.com/ArduPilot/ardupilot
Copter: land mode inits auto yaw
This commit is contained in:
parent
7751352a86
commit
1818360519
|
@ -34,6 +34,9 @@ bool ModeLand::init(bool ignore_checks)
|
|||
// reset flag indicating if pilot has applied roll or pitch inputs during landing
|
||||
copter.ap.land_repo_active = false;
|
||||
|
||||
// initialise yaw
|
||||
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue