APM:Libraries
AP_LeakDetector_Analog.cpp
Go to the documentation of this file.
2 #include <AP_HAL/AP_HAL.h>
3 
4 extern const AP_HAL::HAL& hal;
5 
7  AP_LeakDetector_Backend(_leak_detector, _state)
8 {
10 }
11 
13 {
14  if (source != NULL && leak_detector._pin[state.instance] >= 0) {
16  state.status = source->voltage_average() > 2.0f;
18  } else {
19  state.status = false;
20  }
21 }
virtual float voltage_average()=0
AP_LeakDetector_Analog(AP_LeakDetector &_leak_detector, AP_LeakDetector::LeakDetector_State &_state)
AP_Int8 _pin[LEAKDETECTOR_MAX_INSTANCES]
AP_HAL::AnalogSource * source
#define NULL
Definition: hal_types.h:59
AP_LeakDetector::LeakDetector_State & state
AP_Int8 _default_reading[LEAKDETECTOR_MAX_INSTANCES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual void set_pin(uint8_t p)=0
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
virtual AP_HAL::AnalogSource * channel(int16_t n)=0