Sub: Set neutral controls when switching to manual/acro mode

This commit is contained in:
dheideman 2017-10-30 13:07:58 -07:00 committed by Jacob Walser
parent f5648a8259
commit f34ab3301c
2 changed files with 8 additions and 0 deletions

View File

@ -11,6 +11,10 @@ bool Sub::acro_init()
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
// attitude hold inputs become thrust inputs in acro mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
set_neutral_controls();
return true;
}

View File

@ -6,6 +6,10 @@ bool Sub::manual_init()
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
// attitude hold inputs become thrust inputs in manual mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
set_neutral_controls();
return true;
}