2017-02-07 15:43:01 -04:00
|
|
|
#include "AP_LeakDetector_Analog.h"
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
AP_LeakDetector_Analog::AP_LeakDetector_Analog(AP_LeakDetector &_leak_detector, AP_LeakDetector::LeakDetector_State &_state) :
|
|
|
|
AP_LeakDetector_Backend(_leak_detector, _state)
|
|
|
|
{
|
|
|
|
source = hal.analogin->channel(leak_detector._pin[state.instance]);
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_LeakDetector_Analog::read()
|
|
|
|
{
|
2021-09-22 16:49:42 -03:00
|
|
|
if (source != NULL && leak_detector._pin[state.instance] >= 0 && source->set_pin(leak_detector._pin[state.instance])) {
|
2017-02-07 15:43:01 -04:00
|
|
|
state.status = source->voltage_average() > 2.0f;
|
2021-02-03 10:04:38 -04:00
|
|
|
state.status = state.status != leak_detector._default_reading[state.instance];
|
2017-02-07 15:43:01 -04:00
|
|
|
} else {
|
|
|
|
state.status = false;
|
|
|
|
}
|
|
|
|
}
|