APM:Libraries
AnalogIn_ADS1115.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 #include <AP_ADC/AP_ADC.h>
5 
6 #define ADS1115_ADC_MAX_CHANNELS 6
7 
9 public:
10  friend class AnalogIn_ADS1115;
11  AnalogSource_ADS1115(int16_t pin);
12  float read_average();
13  float read_latest();
14  void set_pin(uint8_t p);
15  void set_stop_pin(uint8_t p) {}
16  void set_settle_time(uint16_t settle_time_ms){}
17  float voltage_average();
18  float voltage_latest();
20 private:
21  int16_t _pin;
22  float _value;
23 };
24 
26 public:
28 
29  void init() override;
30  AP_HAL::AnalogSource *channel(int16_t n) override;
31 
32  /* Board voltage is not available */
33  float board_voltage() override { return 5.0f; }
34 
35 private:
37  void _update();
38 
42 };
#define ADS1115_ADC_MAX_CHANNELS
void set_settle_time(uint16_t settle_time_ms)
friend class AnalogIn_ADS1115
void set_pin(uint8_t p)
float board_voltage() override
AnalogSource_ADS1115(int16_t pin)
uint32_t _last_update_timestamp
void set_stop_pin(uint8_t p)
void init()
Generic board initialization function.
Definition: system.cpp:136
static int8_t pin
Definition: AnalogIn.cpp:15
AP_ADC_ADS1115 * _adc