5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-02 22:18:28 -04:00

HAL_PX4: make ready_to_arm state latching

this fixes a race condition in the handling of the px4io safety switch
This commit is contained in:
Andrew Tridgell 2016-10-24 13:35:39 +11:00
parent 17883f6683
commit 9d6a5c6f04

View File

@ -385,7 +385,11 @@ void PX4RCOutput::_arm_actuators(bool arm)
_armed.timestamp = hrt_absolute_time();
_armed.armed = arm;
_armed.ready_to_arm = arm;
if (arm) {
// this latches ready_to_arm to true once set once. Otherwise
// we have a race condition with px4io safety switch update
_armed.ready_to_arm = true;
}
_armed.lockdown = false;
_armed.force_failsafe = false;