mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Sub: Disable manual control failsafe for SITL
This commit is contained in:
parent
1ec592a2c5
commit
97396e65d1
@ -103,7 +103,10 @@ Sub::Sub(void) :
|
|||||||
sensor_health.compass = true;
|
sensor_health.compass = true;
|
||||||
|
|
||||||
failsafe.last_heartbeat_ms = 0;
|
failsafe.last_heartbeat_ms = 0;
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
failsafe.manual_control = true;
|
failsafe.manual_control = true;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
Sub sub;
|
Sub sub;
|
||||||
|
@ -31,6 +31,7 @@ void Sub::failsafe_battery_event(void)
|
|||||||
|
|
||||||
void Sub::failsafe_manual_control_check()
|
void Sub::failsafe_manual_control_check()
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
uint32_t tnow = AP_HAL::millis();
|
uint32_t tnow = AP_HAL::millis();
|
||||||
|
|
||||||
// Require at least 2Hz update
|
// Require at least 2Hz update
|
||||||
@ -46,6 +47,7 @@ void Sub::failsafe_manual_control_check()
|
|||||||
}
|
}
|
||||||
|
|
||||||
failsafe.manual_control = false;
|
failsafe.manual_control = false;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sub::failsafe_internal_pressure_check()
|
void Sub::failsafe_internal_pressure_check()
|
||||||
|
Loading…
Reference in New Issue
Block a user