mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_PX4: skip the 100ms delay on first px4io safety_state async attempt
This commit is contained in:
parent
e3930b45df
commit
57d6ccc0dd
@ -265,14 +265,14 @@ void PX4RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
|
||||
bool PX4RCOutput::force_safety_on(void)
|
||||
{
|
||||
_safety_state_request = AP_HAL::Util::SAFETY_DISARMED;
|
||||
_safety_state_request_last_ms = AP_HAL::millis();
|
||||
_safety_state_request_last_ms = 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
void PX4RCOutput::force_safety_off(void)
|
||||
{
|
||||
_safety_state_request = AP_HAL::Util::SAFETY_ARMED;
|
||||
_safety_state_request_last_ms = AP_HAL::millis();
|
||||
_safety_state_request_last_ms = 1;
|
||||
}
|
||||
|
||||
void PX4RCOutput::force_safety_pending_requests(void)
|
||||
|
Loading…
Reference in New Issue
Block a user