mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03: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)
|
bool Copter::ModeGuided::init(bool ignore_checks)
|
||||||
{
|
{
|
||||||
if (copter.position_ok() || ignore_checks) {
|
if (copter.position_ok() || ignore_checks) {
|
||||||
// initialise yaw
|
|
||||||
auto_yaw.set_mode_to_default(false);
|
|
||||||
// start in position control mode
|
// start in position control mode
|
||||||
pos_control_start();
|
pos_control_start();
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user