30 #define F4Light_INPUT_MAX_CHANNELS 12 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)) 41 #define ST_VREFINT_CAL MMIO16(0x1FFF7A2A) 42 #define ST_TSENSE_CAL1_30C MMIO16(0x1FFF7A2C) 43 #define ST_TSENSE_CAL2_110 MMIO16(0x1FFF7A2E) 110 return ( 1.2 * 4096 / _vcc.read_average()) * 5.0/3.3;
118 void _timer_event(
void);
130 #define ANALOG_INPUT_F4Light_VCC 253 void set_settle_time(uint16_t settle_time_ms)
const adc_dev *const _ADC1
uint16_t power_status_flags(void)
const adc_dev * _find_device() const
float board_voltage(void)
uint16_t _channel_repeat_count
float voltage_average_ratiometric()
#define F4Light_INPUT_MAX_CHANNELS
AnalogSource(uint8_t pin)
volatile uint16_t _latest
void set_stop_pin(uint8_t pin)
void new_sample(uint16_t)
void init()
Generic board initialization function.
float servorail_voltage(void)
uint32_t _read_start_time_ms
volatile uint32_t _sum_count