APM:Libraries
AnalogIn_ADS1115.cpp
Go to the documentation of this file.
1 #include "AnalogIn_ADS1115.h"
2 
4  _pin(pin),
5  _value(0.0f)
6 {
7 }
8 
10 {
11  if (_pin == pin) {
12  return;
13  }
14  _pin = pin;
15 }
16 
18 {
19  return read_latest();
20 }
21 
23 {
24  return _value;
25 }
26 
28 {
29  return _value;
30 }
31 
33 {
34  return _value;
35 }
36 
38 {
39  return _value;
40 }
41 
42 extern const AP_HAL::HAL &hal;
43 
45 {
46  _adc = new AP_ADC_ADS1115();
47  _channels_number = _adc->get_channels_number();
48 }
49 
51 {
52  for (uint8_t j = 0; j < _channels_number; j++) {
53  if (_channels[j] == nullptr) {
54  _channels[j] = new AnalogSource_ADS1115(pin);
55  return _channels[j];
56  }
57  }
58 
59  hal.console->printf("Out of analog channels\n");
60  return nullptr;
61 }
62 
64 {
65  _adc->init();
66 
70 }
71 
73 {
74  if (AP_HAL::micros() - _last_update_timestamp < 100000) {
75  return;
76  }
77 
79 
80  size_t rc = _adc->read(reports, 6);
81 
82  for (size_t i = 0; i < rc; i++) {
83  for (uint8_t j=0; j < rc; j++) {
84  AnalogSource_ADS1115 *source = _channels[j];
85 
86  if (source != nullptr && reports[i].id == source->_pin) {
87  source->_value = reports[i].data / 1000;
88  }
89  }
90  }
91 
92  _last_update_timestamp = AP_HAL::micros();
93 }
#define ADS1115_ADC_MAX_CHANNELS
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void set_pin(uint8_t p)
static RC_Channel * rc
Definition: RC_Channel.cpp:17
virtual void resume_timer_procs()=0
AnalogSource_ADS1115(int16_t pin)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define f(i)
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 suspend_timer_procs()=0
AP_HAL::AnalogSource * channel(int16_t n) override
uint16_t read() const
Definition: RC_Channel.cpp:325
virtual void register_timer_process(AP_HAL::MemberProc)=0
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static int8_t pin
Definition: AnalogIn.cpp:15
void init() override
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114