Browse Source

Copter: land mode inits auto yaw

master
Randy Mackay 5 years ago
parent
commit
1818360519
  1. 3
      ArduCopter/mode_land.cpp

3
ArduCopter/mode_land.cpp

@ -34,6 +34,9 @@ bool ModeLand::init(bool ignore_checks) @@ -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…
Cancel
Save