Browse Source

SITL: allow testing of throttle-goes-to-low-fixed-value rc failsafes

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
44bc035f7b
  1. 6
      libraries/SITL/SITL.h

6
libraries/SITL/SITL.h

@ -78,6 +78,12 @@ public: @@ -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…
Cancel
Save