5 #define LEAKDETECTOR_MAX_INSTANCES 3 7 #define LEAKDETECTOR_COOLDOWN_MS 3000 // Status will return true for this long after last time leak was detected AP_LeakDetector & operator=(const AP_LeakDetector &)=delete
bool get_status(void) const
AP_Int8 _pin[LEAKDETECTOR_MAX_INSTANCES]
AP_LeakDetector_Backend * _drivers[LEAKDETECTOR_MAX_INSTANCES]
A system for managing and storing variables that are of general interest to the system.
static const struct AP_Param::GroupInfo var_info[]
#define LEAKDETECTOR_MAX_INSTANCES
AP_Int8 _default_reading[LEAKDETECTOR_MAX_INSTANCES]
AP_Int8 _type[LEAKDETECTOR_MAX_INSTANCES]
LeakDetector_State _state[LEAKDETECTOR_MAX_INSTANCES]