APM:Libraries
AP_LeakDetector.cpp
Go to the documentation of this file.
1 #include "AP_LeakDetector.h"
4 
6 
7  // @Param: 1_PIN
8  // @DisplayName: Pin that leak detector is connected to
9  // @Description: Pin that the leak detector is connected to
10  // @Values: -1:Disabled,50:Pixhawk Aux1,51:Pixhawk Aux2,52:Pixhawk Aux3,53:Pixhawk Aux4,54:Pixhawk Aux5,55:Pixhawk Aux6,13:Pixhawk 3.3ADC1,14:Pixhawk 3.3ADC2,15:Pixhawk 6.6ADC
11  // @User: Standard
12  AP_GROUPINFO("1_PIN", 1, AP_LeakDetector, _pin[0], -1),
13 
14  // @Param: 1_LOGIC
15  // @DisplayName: Default reading of leak detector when dry
16  // @Description: Default reading of leak detector when dry
17  // @Values: 0:Low,1:High
18  // @User: Standard
19  AP_GROUPINFO("1_LOGIC", 2, AP_LeakDetector, _default_reading[0], 0),
20 
21 #if LEAKDETECTOR_MAX_INSTANCES > 1
22  // @Param: 2_PIN
23  // @DisplayName: Pin that leak detector is connected to
24  // @Description: Pin that the leak detector is connected to
25  // @Values: -1:Disabled,50:Pixhawk Aux1,51:Pixhawk Aux2,52:Pixhawk Aux3,53:Pixhawk Aux4,54:Pixhawk Aux5,55:Pixhawk Aux6,13:Pixhawk 3.3ADC1,14:Pixhawk 3.3ADC2,15:Pixhawk 6.6ADC
26  // @User: Standard
27  AP_GROUPINFO("2_PIN", 3, AP_LeakDetector, _pin[1], -1),
28 
29  // @Param: 2_LOGIC
30  // @DisplayName: Default reading of leak detector when dry
31  // @Description: Default reading of leak detector when dry
32  // @Values: 0:Low,1:High
33  // @User: Standard
34  AP_GROUPINFO("2_LOGIC", 4, AP_LeakDetector, _default_reading[1], 0),
35 #endif
36 
37 #if LEAKDETECTOR_MAX_INSTANCES > 2
38  // @Param: 3_PIN
39  // @DisplayName: Pin that leak detector is connected to
40  // @Description: Pin that the leak detector is connected to
41  // @Values: -1:Disabled,50:Pixhawk Aux1,51:Pixhawk Aux2,52:Pixhawk Aux3,53:Pixhawk Aux4,54:Pixhawk Aux5,55:Pixhawk Aux6,13:Pixhawk 3.3ADC1,14:Pixhawk 3.3ADC2,15:Pixhawk 6.6ADC
42  // @User: Standard
43  AP_GROUPINFO("3_PIN", 5, AP_LeakDetector, _pin[2], -1),
44 
45  // @Param: 3_LOGIC
46  // @DisplayName: Default reading of leak detector when dry
47  // @Description: Default reading of leak detector when dry
48  // @Values: 0:Low,1:High
49  // @User: Standard
50  AP_GROUPINFO("3_LOGIC", 6, AP_LeakDetector, _default_reading[2], 0),
51 #endif
52 
54 };
55 
57  _status(false),
58  _last_detect_ms(0)
59 {
61 
62  memset(_state,0,sizeof(_state));
63  memset(_drivers,0,sizeof(_drivers));
64 };
65 
67 {
68  for (int i = 0; i < LEAKDETECTOR_MAX_INSTANCES; i++) {
69  switch (_pin[i]) {
70  case 50 ... 55:
71  _state[i].instance = i;
72  _drivers[i] = new AP_LeakDetector_Digital(*this, _state[i]);
73  break;
74  case 13 ... 15:
75  _state[i].instance = i;
76  _drivers[i] = new AP_LeakDetector_Analog(*this, _state[i]);
77  break;
78  default:
79  _drivers[i] = NULL;
80  break;
81  }
82  }
83 }
84 
86 {
87  uint32_t tnow = AP_HAL::millis();
88 
89  for (int i = 0; i < LEAKDETECTOR_MAX_INSTANCES; i++) {
90  if (_drivers[i] != NULL) {
91  _drivers[i]->read();
92  if (_state[i].status) {
93  _last_detect_ms = tnow;
94  }
95  }
96  }
97 
99 
100  return _status;
101 }
102 
104 {
106 }
friend class AP_LeakDetector_Analog
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Int8 _pin[LEAKDETECTOR_MAX_INSTANCES]
AP_LeakDetector_Backend * _drivers[LEAKDETECTOR_MAX_INSTANCES]
virtual void read(void)=0
#define LEAKDETECTOR_COOLDOWN_MS
friend class AP_LeakDetector_Digital
uint32_t millis()
Definition: system.cpp:157
uint32_t _last_detect_ms
static const struct AP_Param::GroupInfo var_info[]
#define NULL
Definition: hal_types.h:59
#define LEAKDETECTOR_MAX_INSTANCES
LeakDetector_State _state[LEAKDETECTOR_MAX_INSTANCES]
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214