AP_LeakDetector.h 1.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  1. #pragma once
  2. #include <AP_Param/AP_Param.h>
  3. #define LEAKDETECTOR_MAX_INSTANCES 3
  4. #define LEAKDETECTOR_COOLDOWN_MS 3000 // Status will return true for this long after last time leak was detected
  5. class AP_LeakDetector_Backend;
  6. class AP_LeakDetector {
  7. friend class AP_LeakDetector_Analog;
  8. friend class AP_LeakDetector_Digital;
  9. public:
  10. AP_LeakDetector();
  11. /* Do not allow copies */
  12. AP_LeakDetector(const AP_LeakDetector &other) = delete;
  13. AP_LeakDetector &operator=(const AP_LeakDetector&) = delete;
  14. enum LeakDetector_Type {
  15. LEAKDETECTOR_TYPE_NONE = 0,
  16. LEAKDETECTOR_TYPE_DIGITAL = 1,
  17. LEAKDETECTOR_TYPE_ANALOG = 2
  18. };
  19. struct LeakDetector_State {
  20. uint8_t instance;
  21. bool status; // leaking?
  22. };
  23. // Return current status
  24. bool get_status(void) const { return _status; }
  25. // Set status externally, ie via mavlink message from subsystems
  26. void set_detect(void);
  27. // Initialize all drivers
  28. void init(void);
  29. // Update all drivers
  30. bool update(void);
  31. static const struct AP_Param::GroupInfo var_info[];
  32. private:
  33. AP_LeakDetector_Backend *_drivers[LEAKDETECTOR_MAX_INSTANCES];
  34. LeakDetector_State _state[LEAKDETECTOR_MAX_INSTANCES];
  35. bool _status; // Current status, true if leak detected, false if all sensors dry
  36. uint32_t _last_detect_ms;
  37. AP_Int8 _type[LEAKDETECTOR_MAX_INSTANCES]; // Analog, Digital, Mavlink
  38. AP_Int8 _pin[LEAKDETECTOR_MAX_INSTANCES]; // Pin that detector is connected to
  39. AP_Int8 _default_reading[LEAKDETECTOR_MAX_INSTANCES]; // Default reading when leak detector is dry
  40. };