APM:Libraries
AP_LeakDetector.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Param/AP_Param.h>
4 
5 #define LEAKDETECTOR_MAX_INSTANCES 3
6 
7 #define LEAKDETECTOR_COOLDOWN_MS 3000 // Status will return true for this long after last time leak was detected
8 
10 
12 
13  friend class AP_LeakDetector_Analog;
15 
16 public:
18 
19  /* Do not allow copies */
20  AP_LeakDetector(const AP_LeakDetector &other) = delete;
21  AP_LeakDetector &operator=(const AP_LeakDetector&) = delete;
22 
27  };
28 
30  uint8_t instance;
31  bool status; // leaking?
32  };
33 
34  // Return current status
35  bool get_status(void) const { return _status; }
36 
37  // Set status externally, ie via mavlink message from subsystems
38  void set_detect(void);
39 
40  // Initialize all drivers
41  void init(void);
42 
43  // Update all drivers
44  bool update(void);
45 
46  static const struct AP_Param::GroupInfo var_info[];
47 
48 private:
51 
52  bool _status; // Current status, true if leak detected, false if all sensors dry
53  uint32_t _last_detect_ms;
54 
55  AP_Int8 _type[LEAKDETECTOR_MAX_INSTANCES]; // Analog, Digital, Mavlink
56  AP_Int8 _pin[LEAKDETECTOR_MAX_INSTANCES]; // Pin that detector is connected to
57  AP_Int8 _default_reading[LEAKDETECTOR_MAX_INSTANCES]; // Default reading when leak detector is dry
58 };
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.
uint32_t _last_detect_ms
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]