mirror of https://github.com/ArduPilot/ardupilot
Sub: Set neutral controls when switching to manual/acro mode
This commit is contained in:
parent
f5648a8259
commit
f34ab3301c
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue