mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
REFACTOR: Remove platform specific defines from ./src/main for ADC
This commit is contained in:
parent
b6d37008f5
commit
44e2fa5477
14 changed files with 66 additions and 44 deletions
|
@ -29,7 +29,7 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
@ -40,11 +40,7 @@
|
||||||
|
|
||||||
adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
|
adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
|
||||||
|
|
||||||
#if defined(STM32F7)
|
|
||||||
volatile FAST_DATA_ZERO_INIT uint16_t adcValues[ADC_CHANNEL_COUNT];
|
volatile FAST_DATA_ZERO_INIT uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||||
#else
|
|
||||||
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
|
||||||
#endif
|
|
||||||
|
|
||||||
uint8_t adcChannelByTag(ioTag_t ioTag)
|
uint8_t adcChannelByTag(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
@ -29,20 +30,6 @@
|
||||||
#define ADC_INSTANCE ADC1
|
#define ADC_INSTANCE ADC1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(APM32F4)
|
|
||||||
#ifndef ADC1_DMA_STREAM
|
|
||||||
#define ADC1_DMA_STREAM DMA2_Stream4 // ST0 or ST4
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef ADC2_DMA_STREAM
|
|
||||||
#define ADC2_DMA_STREAM DMA2_Stream3 // ST2 or ST3
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef ADC3_DMA_STREAM
|
|
||||||
#define ADC3_DMA_STREAM DMA2_Stream0 // ST0 or ST1
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
typedef enum ADCDevice {
|
typedef enum ADCDevice {
|
||||||
ADCINVALID = -1,
|
ADCINVALID = -1,
|
||||||
ADCDEV_1 = 0,
|
ADCDEV_1 = 0,
|
||||||
|
@ -69,28 +56,24 @@ typedef enum {
|
||||||
ADC_CURRENT = 1,
|
ADC_CURRENT = 1,
|
||||||
ADC_EXTERNAL1 = 2,
|
ADC_EXTERNAL1 = 2,
|
||||||
ADC_RSSI = 3,
|
ADC_RSSI = 3,
|
||||||
#if defined(STM32H7) || defined(STM32G4)
|
#if PLATFORM_TRAIT_ADC_INTERNAL
|
||||||
// On H7 and G4, internal sensors are treated in the similar fashion as regular ADC inputs
|
// On H7 and G4, internal sensors are treated in the similar fashion as regular ADC inputs
|
||||||
ADC_CHANNEL_INTERNAL_FIRST_ID = 4,
|
ADC_CHANNEL_INTERNAL_FIRST_ID = 4,
|
||||||
|
|
||||||
ADC_TEMPSENSOR = 4,
|
ADC_TEMPSENSOR = 4,
|
||||||
ADC_VREFINT = 5,
|
ADC_VREFINT = 5,
|
||||||
|
#if PLATFORM_TRAIT_ADC_INTERNAL_VBAT4
|
||||||
ADC_VBAT4 = 6,
|
ADC_VBAT4 = 6,
|
||||||
#elif defined(AT32F435)
|
#endif
|
||||||
ADC_CHANNEL_INTERNAL_FIRST_ID = 4,
|
|
||||||
|
|
||||||
ADC_TEMPSENSOR = 4,
|
|
||||||
ADC_VREFINT = 5,
|
|
||||||
// ADC_VBAT4 = 6,
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
ADC_CHANNEL_COUNT
|
ADC_CHANNEL_COUNT
|
||||||
} AdcChannel;
|
} AdcChannel;
|
||||||
|
|
||||||
typedef struct adcOperatingConfig_s {
|
typedef struct adcOperatingConfig_s {
|
||||||
ioTag_t tag;
|
ioTag_t tag;
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F435)
|
#if PLATFORM_TRAIT_ADC_DEVICE
|
||||||
ADCDevice adcDevice; // ADCDEV_x for this input
|
ADCDevice adcDevice; // ADCDEV_x for this input
|
||||||
|
#endif
|
||||||
|
#if PLATFORM_TRAIT_ADC_CHANNEL_32BIT
|
||||||
uint32_t adcChannel; // Channel number for this input. Note that H7 and G4 HAL requires this to be 32-bit encoded number.
|
uint32_t adcChannel; // Channel number for this input. Note that H7 and G4 HAL requires this to be 32-bit encoded number.
|
||||||
#else
|
#else
|
||||||
uint8_t adcChannel; // ADCy_INxx channel number for this input (XXX May be consolidated with uint32_t case)
|
uint8_t adcChannel; // ADCy_INxx channel number for this input (XXX May be consolidated with uint32_t case)
|
||||||
|
@ -113,6 +96,4 @@ uint16_t adcInternalCompensateVref(uint16_t vrefAdcValue);
|
||||||
int16_t adcInternalComputeTemperature(uint16_t tempAdcValue, uint16_t vrefValue);
|
int16_t adcInternalComputeTemperature(uint16_t tempAdcValue, uint16_t vrefValue);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(SIMULATOR_BUILD)
|
|
||||||
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance);
|
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance);
|
||||||
#endif
|
|
||||||
|
|
|
@ -29,7 +29,6 @@
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
@ -81,7 +80,7 @@ void pgResetFn_adcConfig(adcConfig_t *adcConfig)
|
||||||
#ifdef ADC_CURR_PIN
|
#ifdef ADC_CURR_PIN
|
||||||
adcConfig->current.enabled = true;
|
adcConfig->current.enabled = true;
|
||||||
adcConfig->current.ioTag = IO_TAG(ADC_CURR_PIN);
|
adcConfig->current.ioTag = IO_TAG(ADC_CURR_PIN);
|
||||||
#if defined(STM32H7)
|
#if PLATFORM_TRAIT_ADC_CURRENT_DEVICE
|
||||||
#ifdef ADC_CURR_INSTANCE
|
#ifdef ADC_CURR_INSTANCE
|
||||||
adcConfig->current.device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_CURR_INSTANCE));
|
adcConfig->current.device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_CURR_INSTANCE));
|
||||||
#else
|
#else
|
||||||
|
@ -93,7 +92,7 @@ void pgResetFn_adcConfig(adcConfig_t *adcConfig)
|
||||||
#ifdef ADC_RSSI_PIN
|
#ifdef ADC_RSSI_PIN
|
||||||
adcConfig->rssi.enabled = true;
|
adcConfig->rssi.enabled = true;
|
||||||
adcConfig->rssi.ioTag = IO_TAG(ADC_RSSI_PIN);
|
adcConfig->rssi.ioTag = IO_TAG(ADC_RSSI_PIN);
|
||||||
#if defined(STM32H7)
|
#if PLATFORM_TRAIT_ADC_RSSI_DEVICE
|
||||||
#ifdef ADC_RSSI_INSTANCE
|
#ifdef ADC_RSSI_INSTANCE
|
||||||
adcConfig->rssi.device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_RSSI_INSTANCE));
|
adcConfig->rssi.device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_RSSI_INSTANCE));
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
|
|
@ -150,6 +150,18 @@
|
||||||
|
|
||||||
#if defined(APM32F4)
|
#if defined(APM32F4)
|
||||||
|
|
||||||
|
#ifndef ADC1_DMA_STREAM
|
||||||
|
#define ADC1_DMA_STREAM DMA2_Stream4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ADC2_DMA_STREAM
|
||||||
|
#define ADC2_DMA_STREAM DMA2_Stream3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ADC3_DMA_STREAM
|
||||||
|
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||||
|
#endif
|
||||||
|
|
||||||
//speed is packed inside modebits 5 and 2,
|
//speed is packed inside modebits 5 and 2,
|
||||||
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
|
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
|
||||||
|
|
||||||
|
@ -211,4 +223,5 @@
|
||||||
#define FLASH_CONFIG_BUFFER_TYPE uint32_t
|
#define FLASH_CONFIG_BUFFER_TYPE uint32_t
|
||||||
|
|
||||||
#define DMA_STCH_STRING "Stream"
|
#define DMA_STCH_STRING "Stream"
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -61,7 +61,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
@ -163,14 +163,14 @@ static int adcFindTagMapEntry(const ioTag_t tag)
|
||||||
/**
|
/**
|
||||||
* Setup the scaling offsets and factors used in adc.c
|
* Setup the scaling offsets and factors used in adc.c
|
||||||
* @see src/main/drivers/adc.c
|
* @see src/main/drivers/adc.c
|
||||||
* @see src/main/drivers/adc_impl.h
|
* @see src/platform/common/stm32/platform/adc_impl.h
|
||||||
*
|
*
|
||||||
* There are a number of global calibration/scaling factors used in src/main/drivers/adc.c that need to
|
* There are a number of global calibration/scaling factors used in src/main/drivers/adc.c that need to
|
||||||
* be set to appropriate values if we want to re-use existing code, e.g. adcInternalComputeTemperature
|
* be set to appropriate values if we want to re-use existing code, e.g. adcInternalComputeTemperature
|
||||||
* (the alternative would be to duplicate the code into ST and AT specific versions).
|
* (the alternative would be to duplicate the code into ST and AT specific versions).
|
||||||
* This is made a little confusing since the implementation based on ST datasheets approaches the calculation with
|
* This is made a little confusing since the implementation based on ST datasheets approaches the calculation with
|
||||||
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
||||||
* The constants are defined in src/main/drivers/adc_impl.h. It seems clearest to use the units from
|
* The constants are defined in src/platform/common/stm32/platform/adc_impl.h. It seems clearest to use the units from
|
||||||
* the datasheet when defining those values, so here we have to convert to what's expected in
|
* the datasheet when defining those values, so here we have to convert to what's expected in
|
||||||
* adcInternalComputeTemperature.
|
* adcInternalComputeTemperature.
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -69,6 +69,11 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define READ_REG(REG) ((REG))
|
#define READ_REG(REG) ((REG))
|
||||||
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
|
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
|
||||||
|
|
||||||
|
#define PLATFORM_TRAIT_ADC_INTERNAL 1
|
||||||
|
#define PLATFORM_TRAIT_ADC_INTERNAL_VBAT4 0
|
||||||
|
|
||||||
|
#define PLATFORM_TRAIT_ADC_DEVICE 1
|
||||||
|
#define PLATFORM_TRAIT_ADC_CHANNEL_32BIT 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_USB_MSC
|
#define USE_USB_MSC
|
||||||
|
|
|
@ -32,7 +32,6 @@
|
||||||
|
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "drivers/adc_impl.h"
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/motor_impl.h"
|
#include "drivers/motor_impl.h"
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/adc_impl.h"
|
#include "platform/adc_impl.h"
|
||||||
|
|
||||||
#include "pg/adc.h"
|
#include "pg/adc.h"
|
||||||
|
|
||||||
|
|
|
@ -466,8 +466,36 @@ extern uint8_t _dmaram_end__;
|
||||||
|
|
||||||
#if defined(STM32H7) || defined(STM32G4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
#define DMA_CHANREQ_STRING "Request"
|
#define DMA_CHANREQ_STRING "Request"
|
||||||
|
|
||||||
|
#define PLATFORM_TRAIT_ADC_INTERNAL 1
|
||||||
|
#define PLATFORM_TRAIT_ADC_INTERNAL_VBAT4 1
|
||||||
|
|
||||||
|
#define PLATFORM_TRAIT_ADC_DEVICE 1
|
||||||
|
#define PLATFORM_TRAIT_ADC_CHANNEL_32BIT 1
|
||||||
|
|
||||||
|
#if defined(STM32H7)
|
||||||
|
#define PLATFORM_TRAIT_ADC_CURRENT_DEVICE 1
|
||||||
|
#define PLATFORM_TRAIT_ADC_RSSI_DEVICE 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||||
#define DMA_STCH_STRING "Stream"
|
#define DMA_STCH_STRING "Stream"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(STM32F4) || defined(STM32F7)
|
||||||
|
#ifndef ADC1_DMA_STREAM
|
||||||
|
#define ADC1_DMA_STREAM DMA2_Stream4
|
||||||
|
// ST0 or ST4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ADC2_DMA_STREAM
|
||||||
|
#define ADC2_DMA_STREAM DMA2_Stream3
|
||||||
|
// ST2 or ST3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ADC3_DMA_STREAM
|
||||||
|
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||||
|
// ST0 or ST1
|
||||||
|
#endif
|
||||||
|
#endif
|
|
@ -162,5 +162,6 @@ void adcGetChannelValues(void);
|
||||||
#define TEMPSENSOR_CAL_VREFANALOG (3300U)
|
#define TEMPSENSOR_CAL_VREFANALOG (3300U)
|
||||||
#define TEMPSENSOR_CAL1_TEMP (25U)
|
#define TEMPSENSOR_CAL1_TEMP (25U)
|
||||||
#define TEMPSENSOR_CAL1_V (1.27f)
|
#define TEMPSENSOR_CAL1_V (1.27f)
|
||||||
#define TEMPSENSOR_SLOPE (-4.13f) // mV/C
|
// mV/C
|
||||||
|
#define TEMPSENSOR_SLOPE (-4.13f)
|
||||||
#endif
|
#endif
|
Loading…
Add table
Add a link
Reference in a new issue