mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Sub: Set neutral controls when switching to manual/acro mode
This commit is contained in:
parent
08298fced6
commit
47d5de353d
@ -11,6 +11,10 @@ bool Sub::acro_init()
|
|||||||
// set target altitude to zero for reporting
|
// set target altitude to zero for reporting
|
||||||
pos_control.set_alt_target(0);
|
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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -6,6 +6,10 @@ bool Sub::manual_init()
|
|||||||
// set target altitude to zero for reporting
|
// set target altitude to zero for reporting
|
||||||
pos_control.set_alt_target(0);
|
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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user