APM:Libraries
AnalogIn.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 
18 (c) 2017 night_ghost@ykoctpa.ru
19 
20 based on: Flymaple port by Mike McCauley
21  */
22 
23 #pragma GCC optimize ("O2")
24 
25 
26 
27 #include <AP_HAL/AP_HAL.h>
28 
29 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
30 
32 #include "AnalogIn.h"
33 #include <adc.h>
34 #include <boards.h>
35 #include <gpio_hal.h>
36 #include "GPIO.h"
37 #include "Scheduler.h"
38 #include "c++.h"
39 
40 extern const AP_HAL::HAL& hal;
41 
42 using namespace F4Light;
43 
44 /* CHANNEL_READ_REPEAT: how many reads on a channel before using the value.
45  * This seems to be determined empirically */
46 #define CHANNEL_READ_REPEAT 1
47 
48 
49 
50 
53 
54 
56 
57 
59 
60  // Register _timer_event in the scheduler.
61  void *_task = Scheduler::start_task(FUNCTOR_BIND_MEMBER(&AnalogIn::_timer_event, void), 256); // small stack
62  if(_task){
63  Scheduler::set_task_priority(_task, DRIVER_PRIORITY+1); // slightly less
64  Scheduler::set_task_period(_task, 2000); // setting of period allows task to run
65  }
66 
67  _register_channel(&_vcc); // Register each private channel with AnalogIn.
68 
69  cnv_started=false;
70 }
71 
72 
74 
75 #if 0
76  AnalogSource *ch = new AnalogSource(chnum);
77 #else
78  caddr_t ptr = sbrk_ccm(sizeof(AnalogSource)); // allocate memory in CCM
79  AnalogSource *ch = new(ptr) AnalogSource(chnum);
80 #endif
81 
83  return ch;
84 }
85 
88  AP_HAL::panic("Error: AP_HAL_F4Light::AnalogIn out of channels\r\n");
89  }
91 
92  // *NO* need to lock to increment _num_channels INSPITE OF it is used by the interrupt to access _channels
93  // because we first fill _channels[]
94  _num_channels++;
95 }
96 
97 
99 {
100 
101 
102  if (_num_channels == 0) return; /* No channels are registered - nothing to be done. */
103 
105 
106  if (_channels[_active_channel]->_pin == ANALOG_INPUT_NONE || !_channels[_active_channel]->initialized()) {
108  goto next_channel;
109  }
110 
111  if (cnv_started && !(dev->adcx->SR & ADC_SR_EOC)) {
112  // ADC Conversion is still running - this should not happens, as we are called at 1khz.
113  // SO - more likely we forget to start conversion or some went wrong...
114  // let's fix it
115  adc_start_conv(dev);
116  return;
117  }
118 
121  !_channels[_active_channel]->reading_settled()) {
122  // Start a new conversion on the same channel, throw away the current conversion
123  adc_start_conv(dev);
124 
125  cnv_started=true;
126  return;
127  }
128 
130  if (cnv_started) {
131  uint16_t sample = (uint16_t)(dev->adcx->DR & ADC_DR_DATA);
132  /* Give the active channel a new sample */
134  }
135 
136 next_channel:
137 
138  _channels[_active_channel]->stop_read(); /* stop the previous channel, if a stop pin is defined */
139  _active_channel = (_active_channel + 1) % _num_channels; /* Move to the next channel */
140  _channels[_active_channel]->setup_read(); /* Setup the next channel's conversion */
142 
143  if(dev != NULL) {
144  /* Start conversion */
145  adc_start_conv(dev);
146  cnv_started=true;
147  }
148 
149 }
150 
151 
153 {
154  if ((uint8_t)ch == ANALOG_INPUT_F4Light_VCC) {
155  return &_vcc;
156  } else {
157  return _create_channel((uint8_t)ch);
158  }
159 }
160 
161 #endif
void _register_channel(AnalogSource *)
Definition: AnalogIn.cpp:86
ADC_TypeDef * adcx
Definition: adc.h:15
const adc_dev * _find_device() const
Definition: AnalogIn.h:83
static void set_task_priority(void *h, uint8_t prio)
Definition: Scheduler.h:282
#define DRIVER_PRIORITY
Definition: Scheduler.h:25
#define ANALOG_INPUT_NONE
Definition: AnalogIn.h:56
int16_t _num_channels
Definition: AnalogIn.h:120
caddr_t sbrk_ccm(int nbytes)
Definition: syscalls.c:121
uint16_t _channel_repeat_count
Definition: AnalogIn.h:122
Analog-to-Digital Conversion (ADC) header.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define IN_CCM
Definition: AP_HAL_F4Light.h:9
static void set_task_period(void *h, uint32_t period)
Definition: Scheduler.cpp:914
AP_HAL::AnalogSource * channel(int16_t n)
Definition: AnalogIn.cpp:152
AnalogSource * _create_channel(uint8_t num)
Definition: AnalogIn.cpp:73
#define F4Light_INPUT_MAX_CHANNELS
Definition: AnalogIn.h:30
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AnalogIn.cpp:6
int16_t _active_channel
Definition: AnalogIn.h:121
#define NULL
Definition: hal_types.h:59
Board-specific pin information.
#define ANALOG_INPUT_F4Light_VCC
Definition: AnalogIn.h:130
static void adc_start_conv(const adc_dev *dev)
Definition: adc.h:152
void new_sample(uint16_t)
Definition: adc.h:14
#define CHANNEL_READ_REPEAT
Definition: AnalogIn.cpp:46
void _timer_event(void)
Definition: AnalogIn.cpp:98
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static AnalogSource _vcc
Definition: AnalogIn.h:125
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
Definition: Scheduler.h:266
static AnalogSource * _channels[F4Light_INPUT_MAX_CHANNELS]
Definition: AnalogIn.h:119