APM:Libraries
AnalogSource.cpp
Go to the documentation of this file.
1 /*
3  This program is free software: you can redistribute it and/or modify
4  it under the terms of the GNU General Public License as published by
5  the Free Software Foundation, either version 3 of the License, or
6  (at your option) any later version.
7 
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12 
13  You should have received a copy of the GNU General Public License
14  along with this program. If not, see <http://www.gnu.org/licenses/>.
15  */
16 /*
17  (c) 2017 night_ghost@ykoctpa.ru
18 
19 based on: Flymaple port by Mike McCauley
20  */
21 #pragma GCC optimize ("O2")
22 
23 #include <AP_HAL/AP_HAL.h>
24 
25 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
26 
27 
28 #include "AP_HAL_F4Light.h"
29 
31 
32 #include "AnalogIn.h"
33 #include <adc.h>
34 #include <boards.h>
35 #include <gpio_hal.h>
36 #include "GPIO.h"
37 #include <stm32f4xx.h>
38 #include "Scheduler.h"
39 
40 #pragma GCC optimize ("O2")
41 
42 extern const AP_HAL::HAL& hal;
43 
44 using namespace F4Light;
45 
47  _sum_count(0),
48  _sum(0),
49  _latest(0),
50  _last_average(0),
51  _pin(ANALOG_INPUT_NONE),
52  _stop_pin(ANALOG_INPUT_NONE),
53  _settle_time_ms(0),
54  _read_start_time_ms(0),
55  _init_done(false)
56 {
57  if(pin != ANALOG_INPUT_NONE) {
58  set_pin(pin);
59  }
60 }
61 
62 /*
63  return voltage from 0.0 to 3.3V, scaled to Vcc
64  */
66 {
68 }
69 
71 {
72  return read_latest() * (3.3f / 4096.0f);
73 }
74 
75 /*
76  return voltage from 0.0 to 3.3V, assuming a ratiometric sensor. This
77  means the result is really a pseudo-voltage, that assumes the supply
78  voltage is exactly 3.3V.
79  */
81 {
82  float v = read_average();
83  return v * (3.3f / 4096.0f);
84 }
85 
86 void AnalogSource::set_pin(uint8_t pin) {
87  if (pin != _pin) {
88  noInterrupts();
89  _sum = 0;
90  _sum_count = 0;
91  _last_average = 0;
92  _latest = 0;
93  _pin = pin;
94  interrupts();
95 
96  // ensure the pin is marked as an INPUT pin
97  if (pin != ANALOG_INPUT_NONE && pin != ANALOG_INPUT_F4Light_VCC && pin < BOARD_NR_GPIO_PINS) {
99  }
100 
101  if (pin == ANALOG_INPUT_F4Light_VCC || (pin != ANALOG_INPUT_NONE && pin < BOARD_NR_GPIO_PINS)) {
102  const adc_dev *dev = _find_device();
103 
104  if(dev) {
105  adc_init(dev);
106  adc_enable(dev);
107  }
108  }
109  _init_done=true;
110  }
111 }
112 
113 
114 /* read_average is called from the normal thread (not an interrupt). */
116 {
117 
118  if (_sum_count == 0) {
119  // avoid blocking waiting for new samples
120  return _last_average;
121  }
122 
123  /* Read and clear in a critical section */
127 
128  return _last_average;
129 }
130 
131 
134 
135  const stm32_pin_info &p = PIN_MAP[_stop_pin];
138 
139  }
140  if (_settle_time_ms != 0) {
142  }
143  const adc_dev *dev = _find_device();
144 
146  adc_set_reg_seqlen(dev, 1);
147 
148  /* Enable Vrefint on Channel17 */
150  adc_vref_enable();
151 
152  /* Wait until ADC + Temp sensor start */
154 
155  } else if (_pin == ANALOG_INPUT_NONE) {
156  // nothing to do
157  } else if(dev != NULL && _pin < BOARD_NR_GPIO_PINS) {
158  adc_set_reg_seqlen(dev, 1);
159  uint8_t channel = PIN_MAP[_pin].adc_channel;
161  adc_enable(dev);
162  }
163 }
164 
168  }
170  const adc_dev *dev = _find_device();
171  adc_disable(dev);
172  const stm32_pin_info &p = PIN_MAP[_stop_pin];
175  }
176 }
177 
179 {
181  return false;
182  }
183  return true;
184 }
185 
186 /* new_sample is called from another process */
187 void AnalogSource::new_sample(uint16_t sample) {
188  _latest = sample;
189 
191  _sum += sample;
192 
193 //#define MAX_SUM_COUNT 16 // a legacy of the painfull 8-bit past
194 #define MAX_SUM_COUNT 64
195 
196  if (_sum_count >= MAX_SUM_COUNT) { // F4Light has a 12 bit ADC, so can only sum 16 in a uint16_t - and a 16*65536 in uint32_t
197  _sum /= 2;
199  } else {
200  _sum_count++;
201  }
203 }
204 
205 #endif
void set_pin(uint8_t p)
uint16_t _settle_time_ms
Definition: AnalogIn.h:97
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
static INLINE void noInterrupts()
Definition: exti.h:120
const adc_dev * _find_device() const
Definition: AnalogIn.h:83
static INLINE void interrupts()
Definition: exti.h:106
#define LeaveCriticalSection
Definition: Scheduler.h:40
static void adc_channel_config(const adc_dev *dev, uint8_t channel, uint8_t rank, uint8_t sampleTime)
Definition: adc.h:104
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
#define ANALOG_INPUT_NONE
Definition: AnalogIn.h:56
float read_average()
Definition: AnalogIn.h:53
static void adc_enable(const adc_dev *dev)
Enable an adc peripheral.
Definition: adc.h:131
static void adc_disable(const adc_dev *dev)
Disable an ADC peripheral.
Definition: adc.h:141
Analog-to-Digital Conversion (ADC) header.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
float voltage_average_ratiometric()
static void adc_vref_disable()
Definition: adc.h:163
#define MAX_SUM_COUNT
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void adc_init(const adc_dev *dev)
Initialize an ADC peripheral.
Definition: adc.c:56
uint32_t millis()
Definition: system.cpp:157
AnalogSource(uint8_t pin)
#define ADC_Channel_17
Definition: adc.h:47
float v
Definition: Printf.cpp:15
volatile uint16_t _latest
Definition: AnalogIn.h:89
#define BOARD_NR_GPIO_PINS
Definition: board.h:96
#define NULL
Definition: hal_types.h:59
Board-specific pin information.
#define ADC_SampleTime_84Cycles
Definition: adc.h:58
#define ANALOG_INPUT_F4Light_VCC
Definition: AnalogIn.h:130
void new_sample(uint16_t)
volatile uint32_t _sum
Definition: AnalogIn.h:88
Definition: adc.h:14
uint32_t _read_start_time_ms
Definition: AnalogIn.h:98
static void adc_vref_enable()
Definition: adc.h:158
static void adc_set_reg_seqlen(const adc_dev *dev, uint8_t length)
Set the regular channel sequence length.
Definition: adc.h:86
static int8_t pin
Definition: AnalogIn.cpp:15
static void _delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:305
uint8_t gpio_bit
Definition: boards.h:92
#define EnterCriticalSection
Definition: Scheduler.h:39
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
uint8_t adc_channel
Definition: boards.h:94
const gpio_dev *const gpio_device
Definition: boards.h:89
volatile uint32_t _sum_count
Definition: AnalogIn.h:87
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115