APM:Libraries
AnalogIn.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  Flymaple port by Mike McCauley
17  */
18 
19 #pragma once
20 
21 #include <AP_HAL/AP_HAL.h>
22 
23 #include "AP_HAL_F4Light.h"
24 #include "c++.h"
25 
26 
27 
28 extern void setupADC(void);
29 
30 #define F4Light_INPUT_MAX_CHANNELS 12
31 
32 
33 /* Generic memory-mapped I/O accessor functions */
34 #define MMIO8(addr) (*(volatile uint8_t *)(addr))
35 #define MMIO16(addr) (*(volatile uint16_t *)(addr))
36 #define MMIO32(addr) (*(volatile uint32_t *)(addr))
37 #define MMIO64(addr) (*(volatile uint64_t *)(addr))
38 
39 // from libopencm3/include/libopencm3/stm32/f4/memorymap.h
40 /* ST provided factory calibration values @ 3.3V - this is WRONG! BusFault on this addresses */
41 #define ST_VREFINT_CAL MMIO16(0x1FFF7A2A)
42 #define ST_TSENSE_CAL1_30C MMIO16(0x1FFF7A2C)
43 #define ST_TSENSE_CAL2_110 MMIO16(0x1FFF7A2E)
44 
45 
46 
47 
49 public:
50  friend class F4Light::AnalogIn;
51 
52  AnalogSource(uint8_t pin);
53  float read_average() { return _read_average(); }
54  inline float read_latest() { return _latest; }
55 
56  void set_pin(uint8_t p);
57  inline void set_stop_pin(uint8_t pin) { _stop_pin = pin; }
58  inline void set_settle_time(uint16_t settle_time_ms) { _settle_time_ms = settle_time_ms; }
59  float voltage_average();
60  float voltage_latest();
62 
63  /* implementation specific interface: */
64 
65  /* new_sample(): called with value of ADC measurments, from interrput */
66  void new_sample(uint16_t);
67 
68  /* setup_read(): called to setup ADC registers for next measurment, from interrupt */
69  void setup_read();
70 
71  /* stop_read(): called to stop device measurement */
72  void stop_read();
73 
74  /* reading_settled(): called to check if we have read for long enough */
75  bool reading_settled();
76 
77  /* read_average: called to calculate and clear the internal average.
78  * implements read_average(), unscaled. */
79  float _read_average();
80 
81  inline int16_t get_pin() { return _pin; };
82 protected:
83  const inline adc_dev* _find_device() const { return _ADC1; }
84  inline bool initialized() { return _init_done;}
85 private:
86  /* following three are used from both an interrupt and normal thread */
87  volatile uint32_t _sum_count;
88  volatile uint32_t _sum;
89  volatile uint16_t _latest;
91 
92  /* _pin designates the ADC input mux for the sample */
93  uint8_t _pin;
94 
95  /* _stop_pin designates a digital pin to use for enabling/disabling the analog device */
96  uint8_t _stop_pin;
97  uint16_t _settle_time_ms;
99  bool _init_done;
100 
101 };
102 
103 
105 public:
106  AnalogIn();
107  void init();
108  AP_HAL::AnalogSource* channel(int16_t n);
109  inline float board_voltage(void) {
110  return ( 1.2 * 4096 / _vcc.read_average()) * 5.0/3.3; /*_board_voltage;*/
111  }
112  inline float servorail_voltage(void) { return 0; }
113  inline uint16_t power_status_flags(void) { return 0; }
114 
115 protected:
116  AnalogSource* _create_channel(uint8_t num);
117  void _register_channel(AnalogSource*);
118  void _timer_event(void);
120  int16_t _num_channels;
123 
124 private:
126 
128 };
129 
130 #define ANALOG_INPUT_F4Light_VCC 253
131 
132 
void set_settle_time(uint16_t settle_time_ms)
Definition: AnalogIn.h:58
void set_pin(uint8_t p)
uint16_t _settle_time_ms
Definition: AnalogIn.h:97
const adc_dev *const _ADC1
Definition: adc.c:20
uint16_t power_status_flags(void)
Definition: AnalogIn.h:113
const adc_dev * _find_device() const
Definition: AnalogIn.h:83
float read_average()
Definition: AnalogIn.h:53
int16_t get_pin()
Definition: AnalogIn.h:81
int16_t _num_channels
Definition: AnalogIn.h:120
float board_voltage(void)
Definition: AnalogIn.h:109
uint16_t _channel_repeat_count
Definition: AnalogIn.h:122
float voltage_average_ratiometric()
void setupADC(void)
#define F4Light_INPUT_MAX_CHANNELS
Definition: AnalogIn.h:30
AnalogSource(uint8_t pin)
int16_t _active_channel
Definition: AnalogIn.h:121
volatile uint16_t _latest
Definition: AnalogIn.h:89
void set_stop_pin(uint8_t pin)
Definition: AnalogIn.h:57
void new_sample(uint16_t)
volatile uint32_t _sum
Definition: AnalogIn.h:88
Definition: adc.h:14
void init()
Generic board initialization function.
Definition: system.cpp:136
float servorail_voltage(void)
Definition: AnalogIn.h:112
uint32_t _read_start_time_ms
Definition: AnalogIn.h:98
static int8_t pin
Definition: AnalogIn.cpp:15
void uint32_t num
Definition: systick.h:80
static AnalogSource _vcc
Definition: AnalogIn.h:125
volatile uint32_t _sum_count
Definition: AnalogIn.h:87