mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Plane: force the safety_state immediately because we want it to be in effect while we make mixer changes
This commit is contained in:
parent
4785650c95
commit
e3930b45df
@ -276,6 +276,7 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
// it twice as there have been reports that this call can fail
|
// it twice as there have been reports that this call can fail
|
||||||
// with a small probability
|
// with a small probability
|
||||||
hal.rcout->force_safety_on();
|
hal.rcout->force_safety_on();
|
||||||
|
hal.rcout->force_safety_no_wait();
|
||||||
|
|
||||||
/* reset any existing mixer in px4io. This shouldn't be needed,
|
/* reset any existing mixer in px4io. This shouldn't be needed,
|
||||||
* but is good practice */
|
* but is good practice */
|
||||||
|
Loading…
Reference in New Issue
Block a user