CHEBUZZF3 - Implement ADC driver for 3 ADC channels. Use STM32F3 linker

script so it uses the right values for RAM and FLASH size.
This commit is contained in:
Dominic Clifton 2014-05-12 00:17:14 +01:00
parent b3ee895f97
commit 4be9d953ac
9 changed files with 398 additions and 89 deletions

View File

@ -58,6 +58,8 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(CMSIS_DIR)/CM1/CoreSupport \ $(CMSIS_DIR)/CM1/CoreSupport \
$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \ $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x \
LD_SCRIPT = $(ROOT)/stm32_flash_f303.ld
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 ARCH_FLAGS = -mthumb -mcpu=cortex-m4
DEVICE_FLAGS = -DSTM32F303xC DEVICE_FLAGS = -DSTM32F303xC
TARGET_FLAGS = -D$(TARGET) TARGET_FLAGS = -D$(TARGET)
@ -81,6 +83,8 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(CMSIS_DIR)/CM3/CoreSupport \ $(CMSIS_DIR)/CM3/CoreSupport \
$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
LD_SCRIPT = $(ROOT)/stm32_flash_f103.ld
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 ARCH_FLAGS = -mthumb -mcpu=cortex-m3
TARGET_FLAGS = -D$(TARGET) TARGET_FLAGS = -D$(TARGET)
DEVICE_FLAGS = -DSTM32F10X_MD DEVICE_FLAGS = -DSTM32F10X_MD
@ -139,6 +143,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_mpu3050.c \ drivers/accgyro_mpu3050.c \
drivers/accgyro_mpu6050.c \ drivers/accgyro_mpu6050.c \
drivers/adc_common.c \ drivers/adc_common.c \
drivers/adc_stm32f10x.c \
drivers/barometer_bmp085.c \ drivers/barometer_bmp085.c \
drivers/barometer_ms5611.c \ drivers/barometer_ms5611.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
@ -170,6 +175,7 @@ FY90Q_SRC = startup_stm32f10x_md_gcc.S \
OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/accgyro_mpu6050.c \ drivers/accgyro_mpu6050.c \
drivers/adc_common.c \ drivers/adc_common.c \
drivers/adc_stm32f10x.c \
drivers/bus_i2c_stm32f10x.c \ drivers/bus_i2c_stm32f10x.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
drivers/gpio_stm32f10x.c \ drivers/gpio_stm32f10x.c \
@ -186,6 +192,7 @@ STM32F3DISCOVERY_COMMON_SRC = startup_stm32f30x_md_gcc.S \
drivers/accgyro_l3gd20.c \ drivers/accgyro_l3gd20.c \
drivers/accgyro_lsm303dlhc.c \ drivers/accgyro_lsm303dlhc.c \
drivers/adc_common.c \ drivers/adc_common.c \
drivers/adc_stm32f30x.c \
drivers/bus_i2c_stm32f30x.c \ drivers/bus_i2c_stm32f30x.c \
drivers/bus_spi.c \ drivers/bus_spi.c \
drivers/gpio_stm32f30x.c \ drivers/gpio_stm32f30x.c \
@ -246,7 +253,6 @@ ASFLAGS = $(ARCH_FLAGS) \
$(addprefix -I,$(INCLUDE_DIRS)) $(addprefix -I,$(INCLUDE_DIRS))
# XXX Map/crossref output? # XXX Map/crossref output?
LD_SCRIPT = $(ROOT)/stm32_flash.ld
LDFLAGS = -lm \ LDFLAGS = -lm \
$(ARCH_FLAGS) \ $(ARCH_FLAGS) \
-static \ -static \

View File

@ -4,95 +4,33 @@
#include "platform.h" #include "platform.h"
#include "system_common.h" #include "system_common.h"
#include "sensors_common.h" // FIXME dependency into the main code
#include "accgyro_common.h" #include "accgyro_common.h"
#include "adc_common.h" #include "adc_common.h"
// Driver for STM32F103CB onboard ADC adc_config_t adcConfig[ADC_CHANNEL_COUNT];
// VBAT is connected to PA4 (ADC1_IN4) with 10k:1k divider volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
// rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board uint8_t adcChannelCount = 0;
// Additional channel can be stolen from RC_CH2 (PA1, ADC1_IN1) or
// RC_CH8 (PB1, ADC1_IN9) by using set power_adc_channel=1|9
typedef struct adc_config_t { extern int16_t debug[4];
uint8_t adcChannel; // ADC1_INxx channel number
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
} adc_config_t;
static adc_config_t adcConfig[ADC_CHANNEL_MAX];
static volatile uint16_t adcValues[ADC_CHANNEL_MAX];
void adcInit(drv_adc_config_t *init)
{
#ifndef STM32F3DISCOVERY
ADC_InitTypeDef adc;
DMA_InitTypeDef dma;
int numChannels = 1, i;
// configure always-present battery index (ADC4)
adcConfig[ADC_BATTERY].adcChannel = ADC_Channel_4;
adcConfig[ADC_BATTERY].dmaIndex = numChannels - 1;
// optional ADC5 input on rev.5 hardware
if (hse_value == 12000000) {
numChannels++;
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_5;
adcConfig[ADC_EXTERNAL1].dmaIndex = numChannels - 1;
}
// another channel can be stolen from PWM for current measurement or other things
if (init->powerAdcChannel > 0) {
numChannels++;
adcConfig[ADC_EXTERNAL2].adcChannel = init->powerAdcChannel;
adcConfig[ADC_EXTERNAL2].dmaIndex = numChannels - 1;
}
// ADC driver assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(DMA1_Channel1);
dma.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
dma.DMA_MemoryBaseAddr = (uint32_t)adcValues;
dma.DMA_DIR = DMA_DIR_PeripheralSRC;
dma.DMA_BufferSize = numChannels;
dma.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma.DMA_MemoryInc = numChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
dma.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma.DMA_Mode = DMA_Mode_Circular;
dma.DMA_Priority = DMA_Priority_High;
dma.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &dma);
DMA_Cmd(DMA1_Channel1, ENABLE);
adc.ADC_Mode = ADC_Mode_Independent;
adc.ADC_ScanConvMode = numChannels > 1 ? ENABLE : DISABLE;
adc.ADC_ContinuousConvMode = ENABLE;
adc.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
adc.ADC_DataAlign = ADC_DataAlign_Right;
adc.ADC_NbrOfChannel = numChannels;
ADC_Init(ADC1, &adc);
// fixed ADC4
ADC_RegularChannelConfig(ADC1, ADC_Channel_4, 1, ADC_SampleTime_28Cycles5);
// configure any additional ADC channels (2 + n)
for (i = 1; i < numChannels; i++)
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, i + 1, ADC_SampleTime_28Cycles5);
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
// Calibrate ADC
ADC_ResetCalibration(ADC1);
while(ADC_GetResetCalibrationStatus(ADC1));
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1));
// Fire off ADC
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
#endif
}
uint16_t adcGetChannel(uint8_t channel) uint16_t adcGetChannel(uint8_t channel)
{ {
#if 0
switch(adcChannelCount) {
case 3:
debug[2] = adcValues[adcConfig[2].dmaIndex];
/* no break */
case 2:
debug[1] = adcValues[adcConfig[1].dmaIndex];
/* no break */
case 1:
debug[0] = adcValues[adcConfig[0].dmaIndex];
/* no break */
default:
break;
}
#endif
return adcValues[adcConfig[channel].dmaIndex]; return adcValues[adcConfig[channel].dmaIndex];
} }

View File

@ -4,9 +4,16 @@ typedef enum {
ADC_BATTERY = 0, ADC_BATTERY = 0,
ADC_EXTERNAL1 = 1, ADC_EXTERNAL1 = 1,
ADC_EXTERNAL2 = 2, ADC_EXTERNAL2 = 2,
ADC_CHANNEL_MAX = 3 ADC_CHANNEL_MAX = ADC_EXTERNAL2
} AdcChannel; } AdcChannel;
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
typedef struct adc_config_t {
uint8_t adcChannel; // ADC1_INxx channel number
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
} adc_config_t;
typedef struct drv_adc_config_t { typedef struct drv_adc_config_t {
uint8_t powerAdcChannel; // which channel used for current monitor, allowed PA1, PB1 (ADC_Channel_1, ADC_Channel_9) uint8_t powerAdcChannel; // which channel used for current monitor, allowed PA1, PB1 (ADC_Channel_1, ADC_Channel_9)
} drv_adc_config_t; } drv_adc_config_t;

View File

@ -0,0 +1,88 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "system_common.h"
#include "sensors_common.h" // FIXME dependency into the main code
#include "accgyro_common.h"
#include "adc_common.h"
// Driver for STM32F103CB onboard ADC
// VBAT is connected to PA4 (ADC1_IN4) with 10k:1k divider
// rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
// Additional channel can be stolen from RC_CH2 (PA1, ADC1_IN1) or
// RC_CH8 (PB1, ADC1_IN9) by using set power_adc_channel=1|9
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelCount;
void adcInit(drv_adc_config_t *init)
{
ADC_InitTypeDef adc;
DMA_InitTypeDef dma;
uint8_t i;
// configure always-present battery index (ADC4)
adcConfig[ADC_BATTERY].adcChannel = ADC_Channel_4;
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount - 1;
// optional ADC5 input on rev.5 hardware
if (hse_value == 12000000) {
adcChannelCount++;
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_5;
adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount - 1;
}
// another channel can be stolen from PWM for current measurement or other things
if (init->powerAdcChannel > 0) {
adcChannelCount++;
adcConfig[ADC_EXTERNAL2].adcChannel = init->powerAdcChannel;
adcConfig[ADC_EXTERNAL2].dmaIndex = adcChannelCount - 1;
}
// ADC driver assumes all the GPIO was already placed in 'AIN' mode
DMA_DeInit(DMA1_Channel1);
dma.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
dma.DMA_MemoryBaseAddr = (uint32_t)adcValues;
dma.DMA_DIR = DMA_DIR_PeripheralSRC;
dma.DMA_BufferSize = adcChannelCount;
dma.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma.DMA_MemoryInc = adcChannelCount > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
dma.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma.DMA_Mode = DMA_Mode_Circular;
dma.DMA_Priority = DMA_Priority_High;
dma.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &dma);
DMA_Cmd(DMA1_Channel1, ENABLE);
adc.ADC_Mode = ADC_Mode_Independent;
adc.ADC_ScanConvMode = adcChannelCount > 1 ? ENABLE : DISABLE;
adc.ADC_ContinuousConvMode = ENABLE;
adc.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
adc.ADC_DataAlign = ADC_DataAlign_Right;
adc.ADC_NbrOfChannel = adcChannelCount;
ADC_Init(ADC1, &adc);
// fixed ADC4
ADC_RegularChannelConfig(ADC1, ADC_Channel_4, 1, ADC_SampleTime_28Cycles5);
// configure any additional ADC channels (2 + n)
for (i = 1; i < adcChannelCount; i++)
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, i + 1, ADC_SampleTime_28Cycles5);
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
// Calibrate ADC
ADC_ResetCalibration(ADC1);
while(ADC_GetResetCalibrationStatus(ADC1));
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1));
// Fire off ADC
ADC_SoftwareStartConvCmd(ADC1, ENABLE);
}

111
src/drivers/adc_stm32f30x.c Normal file
View File

@ -0,0 +1,111 @@
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "sensors_common.h" // FIXME dependency into the main code
#include "accgyro_common.h"
#include "adc_common.h"
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
uint8_t adcChannelCount;
void adcInit(drv_adc_config_t *init)
{
ADC_InitTypeDef ADC_InitStructure;
DMA_InitTypeDef DMA_InitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
uint8_t i;
adcConfig[ADC_BATTERY].adcChannel = ADC_Channel_6;
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
adcChannelCount++;
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_7;
adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount;
adcChannelCount++;
adcConfig[ADC_EXTERNAL2].adcChannel = ADC_Channel_8;
adcConfig[ADC_EXTERNAL2].dmaIndex = adcChannelCount;
adcChannelCount++;
DMA_DeInit(DMA1_Channel1);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = adcChannelCount;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = adcChannelCount > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &DMA_InitStructure);
DMA_Cmd(DMA1_Channel1, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
GPIO_Init(GPIOC, &GPIO_InitStructure);
// calibrate
ADC_VoltageRegulatorCmd(ADC1, ENABLE);
delay(10);
ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single);
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1) != RESET);
ADC_VoltageRegulatorCmd(ADC1, DISABLE);
ADC_CommonInitTypeDef ADC_CommonInitStructure;
ADC_CommonStructInit(&ADC_CommonInitStructure);
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_CommonInitStructure.ADC_Clock = ADC_Clock_SynClkModeDiv4;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1;
ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0;
ADC_CommonInit(ADC1, &ADC_CommonInitStructure);
ADC_StructInit(&ADC_InitStructure);
ADC_InitStructure.ADC_ContinuousConvMode = ADC_ContinuousConvMode_Enable;
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ExternalTrigConvEvent = ADC_ExternalTrigConvEvent_0;
ADC_InitStructure.ADC_ExternalTrigEventEdge = ADC_ExternalTrigEventEdge_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_OverrunMode = ADC_OverrunMode_Disable;
ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable;
ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount;
ADC_Init(ADC1, &ADC_InitStructure);
for (i = 0; i < adcChannelCount; i++)
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, i + 1, ADC_SampleTime_181Cycles5);
ADC_Cmd(ADC1, ENABLE);
while(!ADC_GetFlagStatus(ADC1, ADC_FLAG_RDY));
ADC_DMAConfig(ADC1, ADC_DMAMode_Circular);
ADC_DMACmd(ADC1, ENABLE);
ADC_StartConversion(ADC1);
}

View File

@ -103,6 +103,8 @@ void systemInit(bool overclock)
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
#endif #endif
#ifdef STM32F303xC #ifdef STM32F303xC
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
RCC_APB1PeriphClockCmd( RCC_APB1PeriphClockCmd(
RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM2 |
RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM3 |
@ -143,7 +145,7 @@ void systemInit(bool overclock)
gpio.mode = Mode_AIN; gpio.mode = Mode_AIN;
gpio.pin = Pin_All; gpio.pin = Pin_All;
#ifdef STM32F3DISCOVERY #ifdef STM32F3DISCOVERY
gpio.pin = Pin_All & ~(Pin_13|Pin_14); gpio.pin = Pin_All & ~(Pin_13|Pin_14|Pin_15); // Leave JTAG pins alone
gpioInit(GPIOA, &gpio); gpioInit(GPIOA, &gpio);
gpio.pin = Pin_All; gpio.pin = Pin_All;
#else #else
@ -151,6 +153,13 @@ void systemInit(bool overclock)
#endif #endif
gpioInit(GPIOB, &gpio); gpioInit(GPIOB, &gpio);
gpioInit(GPIOC, &gpio); gpioInit(GPIOC, &gpio);
#ifdef STM32F303xC
gpioInit(GPIOD, &gpio);
gpioInit(GPIOE, &gpio);
#ifdef CHEBUZZF3
gpioInit(GPIOF, &gpio);
#endif
#endif
#ifdef STM32F10X_MD #ifdef STM32F10X_MD
// Turn off JTAG port 'cause we're using the GPIO for leds // Turn off JTAG port 'cause we're using the GPIO for leds

150
stm32_flash_f303.ld Normal file
View File

@ -0,0 +1,150 @@
/*
*****************************************************************************
**
** File : stm32_flash.ld
**
** Abstract : Linker script for STM32F103C8 Device with
** 128KByte FLASH, 20KByte RAM
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x2000A000; /* end of 40K RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 254K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(.fini_array*))
KEEP (*(SORT(.fini_array.*)))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = .;
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* MEMORY_bank1 section, code must be located here explicitly */
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
.memory_b1_text :
{
*(.mb1text) /* .mb1text sections (code) */
*(.mb1text*) /* .mb1text* sections (code) */
*(.mb1rodata) /* read-only data (constants) */
*(.mb1rodata*)
} >MEMORY_B1
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@ -55,10 +55,10 @@ GPIOB 3 / PB3 / Ext 4
There are some solder pads labelled ADC0-3 & Diff Press at the top left inner of the board There are some solder pads labelled ADC0-3 & Diff Press at the top left inner of the board
They are connected to the ADC socket at the top left outer of the board They are connected to the ADC socket at the top left outer of the board
PC3 / Diff Press (Differential Pressure) PC3 / Diff Press - ADC12_IN9 (Differential Pressure)
PC2 / ADC2 PC2 / ADC2 - ADC12_IN8
PC1 / ADC1 PC1 / ADC1 - ADC12_IN7
PC0 / ADC0 PC0 / ADC0 - ADC12_IN6
There is space for a MPXV5004/MPVZ5004 differential pressure sensor, if populated it's analog pin connects to PC3. There is space for a MPXV5004/MPVZ5004 differential pressure sensor, if populated it's analog pin connects to PC3.