mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
SITL: allow testing of throttle-goes-to-low-fixed-value rc failsafes
This commit is contained in:
parent
5a19f447a7
commit
44bc035f7b
@ -78,6 +78,12 @@ public:
|
||||
static SITL *_singleton;
|
||||
static SITL *get_singleton() { return _singleton; }
|
||||
|
||||
enum SITL_RCFail {
|
||||
SITL_RCFail_None = 0,
|
||||
SITL_RCFail_NoPulses = 1,
|
||||
SITL_RCFail_Throttle950 = 2,
|
||||
};
|
||||
|
||||
enum GPSType {
|
||||
GPS_TYPE_NONE = 0,
|
||||
GPS_TYPE_UBLOX = 1,
|
||||
|
Loading…
Reference in New Issue
Block a user