Add analogin, serial and spi support for NUCLEO_F103RB

pull/118/head
bcostm 2013-11-19 09:11:31 +01:00
parent 70dd0d891e
commit 415ac34b56
8 changed files with 1067 additions and 8 deletions

View File

@ -0,0 +1,313 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_md.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
;*******************************************************************************
; Amount of memory (in bytes) allocated for Stack
; Tailor this value to your application needs
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x00000400
AREA STACK, NOINIT, READWRITE, ALIGN=3
EXPORT __initial_sp
Stack_Mem SPACE Stack_Size
__initial_sp EQU 0x20000000 ; Top of RAM
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000000
AREA HEAP, NOINIT, READWRITE, ALIGN=3
EXPORT __heap_base
EXPORT __heap_limit
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD MemManage_Handler ; MPU Fault Handler
DCD BusFault_Handler ; Bus Fault Handler
DCD UsageFault_Handler ; Usage Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD DebugMon_Handler ; Debug Monitor Handler
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD WWDG_IRQHandler ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1
DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2
DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3
DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4
DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5
DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6
DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7
DCD ADC1_2_IRQHandler ; ADC1_2
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_IRQHandler ; TIM1 Break
DCD TIM1_UP_IRQHandler ; TIM1 Update
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
IMPORT SystemInit
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
MemManage_Handler\
PROC
EXPORT MemManage_Handler [WEAK]
B .
ENDP
BusFault_Handler\
PROC
EXPORT BusFault_Handler [WEAK]
B .
ENDP
UsageFault_Handler\
PROC
EXPORT UsageFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
DebugMon_Handler\
PROC
EXPORT DebugMon_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WWDG_IRQHandler [WEAK]
EXPORT PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_IRQHandler [WEAK]
EXPORT RCC_IRQHandler [WEAK]
EXPORT EXTI0_IRQHandler [WEAK]
EXPORT EXTI1_IRQHandler [WEAK]
EXPORT EXTI2_IRQHandler [WEAK]
EXPORT EXTI3_IRQHandler [WEAK]
EXPORT EXTI4_IRQHandler [WEAK]
EXPORT DMA1_Channel1_IRQHandler [WEAK]
EXPORT DMA1_Channel2_IRQHandler [WEAK]
EXPORT DMA1_Channel3_IRQHandler [WEAK]
EXPORT DMA1_Channel4_IRQHandler [WEAK]
EXPORT DMA1_Channel5_IRQHandler [WEAK]
EXPORT DMA1_Channel6_IRQHandler [WEAK]
EXPORT DMA1_Channel7_IRQHandler [WEAK]
EXPORT ADC1_2_IRQHandler [WEAK]
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_IRQHandler [WEAK]
EXPORT EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_IRQHandler [WEAK]
EXPORT TIM1_UP_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBWakeUp_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_IRQHandler
RCC_IRQHandler
EXTI0_IRQHandler
EXTI1_IRQHandler
EXTI2_IRQHandler
EXTI3_IRQHandler
EXTI4_IRQHandler
DMA1_Channel1_IRQHandler
DMA1_Channel2_IRQHandler
DMA1_Channel3_IRQHandler
DMA1_Channel4_IRQHandler
DMA1_Channel5_IRQHandler
DMA1_Channel6_IRQHandler
DMA1_Channel7_IRQHandler
ADC1_2_IRQHandler
USB_HP_CAN1_TX_IRQHandler
USB_LP_CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBWakeUp_IRQHandler
B .
ENDP
ALIGN
;*******************************************************************************
; User Stack and Heap initialization
;*******************************************************************************
;IF :DEF:__MICROLIB
;EXPORT __initial_sp
;EXPORT __heap_base
;EXPORT __heap_limit
;ELSE
;IMPORT __use_two_region_memory
;EXPORT __user_initial_stackheap
;__user_initial_stackheap
;LDR R0, = Heap_Mem
;LDR R1, =(Stack_Mem + Stack_Size)
;LDR R2, = (Heap_Mem + Heap_Size)
;LDR R3, = Stack_Mem
;BX LR
;ALIGN
;ENDIF
END
;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE*****

View File

@ -0,0 +1,19 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x08000000 0x20000 { ; load region size_region (128K)
ER_IROM1 0x08000000 0x20000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
; 59 vectors (16 core + 43 peripheral) * 4 bytes = 236 bytes to reserve (0xEC)
RW_IRAM1 (0x20000000+0xEC) (0x5000-0xEC) { ; RW data
.ANY (+RW +ZI)
}
}

View File

@ -0,0 +1,31 @@
/* mbed Microcontroller Library - stackheap
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
*
* Setup a fixed single stack/heap memory model,
* between the top of the RW/ZI region and the stackpointer
*/
#ifdef __cplusplus
extern "C" {
#endif
#include <rt_misc.h>
#include <stdint.h>
extern char Image$$RW_IRAM1$$ZI$$Limit[];
extern __value_in_regs struct __initial_stackheap __user_setup_stackheap(uint32_t R0, uint32_t R1, uint32_t R2, uint32_t R3) {
uint32_t zi_limit = (uint32_t)Image$$RW_IRAM1$$ZI$$Limit;
uint32_t sp_limit = __current_sp();
zi_limit = (zi_limit + 7) & ~0x7; // ensure zi_limit is 8-byte aligned
struct __initial_stackheap r;
r.heap_base = zi_limit;
r.heap_limit = sp_limit;
return r;
}
#ifdef __cplusplus
}
#endif

View File

@ -2,17 +2,18 @@
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x08000000 0x00010000 { ; load region size_region
ER_IROM1 0x08000000 0x00010000 { ; load address = execution address
LR_IROM1 0x08000000 0x20000 { ; load region size_region (128K)
ER_IROM1 0x08000000 0x20000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
;RW_IRAM1 0x20000000 0x00005000 { ; RW data
; 59 vectors (16 core + 43 peripheral) * 4 bytes = 236 bytes to reserve (0xEC)
; 20KB - 0xEC = 0x5000 - 0xEC = 0x4F14 bytes after reserved area
RW_IRAM1 0x200000EC 0x00004F14 { ; RW data
RW_IRAM1 (0x20000000+0xEC) (0x5000-0xEC) { ; RW data
.ANY (+RW +ZI)
}
}

View File

@ -0,0 +1,104 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
//==============================================================================
// STM32F103
//==============================================================================
#include "analogin_api.h"
#include "wait_api.h"
#if DEVICE_ANALOGIN
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
static const PinMap PinMap_ADC[] = {
{PA_0, ADC_1, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{PA_1, ADC_1, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{PA_4, ADC_1, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{PB_0, ADC_2, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{PC_1, ADC_2, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{PC_0, ADC_2, STM_PIN_DATA(GPIO_Mode_AIN, 0)},
{NC, NC, 0}
};
void analogin_init(analogin_t *obj, PinName pin) {
ADC_TypeDef *adc;
ADC_InitTypeDef ADC_InitStructure;
// Get the peripheral name (ADC_1, ADC_2...) from the pin and assign it to the object
obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
if (obj->adc == (ADCName)NC) {
error("ADC pin mapping failed");
}
// Get ADC registers structure address
adc = (ADC_TypeDef *)(obj->adc);
// Enable ADC clock
RCC_ADCCLKConfig(RCC_PCLK2_Div4);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE);
// Configure GPIO
pinmap_pinout(pin, PinMap_ADC);
// Configure ADC
ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_InitStructure.ADC_ScanConvMode = DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfChannel = 1;
ADC_Init(adc, &ADC_InitStructure);
// Configure ADC channel
if (pin == PA_0) { ADC_RegularChannelConfig(adc, ADC_Channel_0, 1, ADC_SampleTime_7Cycles5); }
if (pin == PA_1) { ADC_RegularChannelConfig(adc, ADC_Channel_1, 1, ADC_SampleTime_7Cycles5); }
if (pin == PA_4) { ADC_RegularChannelConfig(adc, ADC_Channel_4, 1, ADC_SampleTime_7Cycles5); }
if (pin == PB_0) { ADC_RegularChannelConfig(adc, ADC_Channel_8, 1, ADC_SampleTime_7Cycles5); }
if (pin == PC_1) { ADC_RegularChannelConfig(adc, ADC_Channel_11, 1, ADC_SampleTime_7Cycles5); }
if (pin == PC_0) { ADC_RegularChannelConfig(adc, ADC_Channel_10, 1, ADC_SampleTime_7Cycles5); }
// Enable ADC
ADC_Cmd(adc, ENABLE);
// Calibrate ADC
ADC_ResetCalibration(adc);
while(ADC_GetResetCalibrationStatus(adc));
ADC_StartCalibration(adc);
while(ADC_GetCalibrationStatus(adc));
}
static inline uint16_t adc_read(analogin_t *obj) {
// Get ADC registers structure address
ADC_TypeDef *adc = (ADC_TypeDef *)(obj->adc);
ADC_SoftwareStartConvCmd(adc, ENABLE); // Start conversion
while(ADC_GetFlagStatus(adc, ADC_FLAG_EOC) == RESET); // Wait end of conversion
return(ADC_GetConversionValue(adc)); // Get conversion value
}
uint16_t analogin_read_u16(analogin_t *obj) {
return(adc_read(obj));
}
float analogin_read(analogin_t *obj) {
uint16_t value = adc_read(obj);
return (float)value * (1.0f / (float)0xFFF); // 12 bits range
}
#endif

View File

@ -22,15 +22,15 @@
#define DEVICE_INTERRUPTIN 0
#define DEVICE_ANALOGIN 0
#define DEVICE_ANALOGIN 1
#define DEVICE_ANALOGOUT 0
#define DEVICE_SERIAL 0
#define DEVICE_SERIAL 1
#define DEVICE_I2C 0
#define DEVICE_I2CSLAVE 0
#define DEVICE_SPI 0
#define DEVICE_SPI 1
#define DEVICE_SPISLAVE 0
#define DEVICE_RTC 0

View File

@ -0,0 +1,310 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
//==============================================================================
// STM32F103
//==============================================================================
#include "serial_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
#include <string.h>
/******************************************************************************
* INITIALIZATION
******************************************************************************/
static const PinMap PinMap_UART_TX[] = {
{PA_9, UART_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 0)},
{PA_2, UART_2, STM_PIN_DATA(GPIO_Mode_AF_PP, 0)},
{NC, NC, 0}
};
static const PinMap PinMap_UART_RX[] = {
{PA_10, UART_1, STM_PIN_DATA(GPIO_Mode_IN_FLOATING, 0)},
{PA_3, UART_2, STM_PIN_DATA(GPIO_Mode_IN_FLOATING, 0)},
{NC, NC, 0}
};
#define UART_NUM (2)
static uint32_t serial_irq_ids[UART_NUM] = {0};
static uart_irq_handler irq_handler;
int stdio_uart_inited = 0;
serial_t stdio_uart;
void serial_init(serial_t *obj, PinName tx, PinName rx) {
USART_TypeDef *usart;
USART_InitTypeDef USART_InitStructure;
// Determine the UART to use (UART_1, UART_2, ...)
UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX);
UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX);
// Get the peripheral name (UART_1, UART_2, ...) from the pin and assign it to the object
obj->uart = (UARTName)pinmap_merge(uart_tx, uart_rx);
if (obj->uart == (UARTName)NC) {
error("Serial pinout mapping failed");
}
// Get UART registers structure address
usart = (USART_TypeDef *)(obj->uart);
// Enable USART clock
if (obj->uart == UART_1) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
}
if (obj->uart == UART_2) {
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
}
// Configure the UART pins
pinmap_pinout(tx, PinMap_UART_TX);
pinmap_pinout(rx, PinMap_UART_RX);
// Configure UART
obj->baudrate = 9600;
obj->databits = USART_WordLength_8b;
obj->stopbits = USART_StopBits_1;
obj->parity = USART_Parity_No;
USART_InitStructure.USART_BaudRate = obj->baudrate;
USART_InitStructure.USART_WordLength = obj->databits;
USART_InitStructure.USART_StopBits = obj->stopbits;
USART_InitStructure.USART_Parity = obj->parity;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(usart, &USART_InitStructure);
USART_Cmd(usart, ENABLE);
// The index is used by irq
if (obj->uart == UART_1) obj->index = 0;
if (obj->uart == UART_2) obj->index = 1;
// For stdio management
if (obj->uart == STDIO_UART) {
stdio_uart_inited = 1;
memcpy(&stdio_uart, obj, sizeof(serial_t));
}
}
void serial_free(serial_t *obj) {
serial_irq_ids[obj->index] = 0;
}
void serial_baud(serial_t *obj, int baudrate) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
USART_InitTypeDef USART_InitStructure;
// Save new value
obj->baudrate = baudrate;
USART_Cmd(usart, DISABLE);
USART_InitStructure.USART_BaudRate = obj->baudrate;
USART_InitStructure.USART_WordLength = obj->databits;
USART_InitStructure.USART_StopBits = obj->stopbits;
USART_InitStructure.USART_Parity = obj->parity;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(usart, &USART_InitStructure);
USART_Cmd(usart, ENABLE);
}
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
USART_InitTypeDef USART_InitStructure;
// Save new values
if (data_bits == 8) {
obj->databits = USART_WordLength_8b;
}
else {
obj->databits = USART_WordLength_9b;
}
switch (parity) {
case ParityOdd:
case ParityForced0:
obj->parity = USART_Parity_Odd;
break;
case ParityEven:
case ParityForced1:
obj->parity = USART_Parity_Even;
break;
default: // ParityNone
obj->parity = USART_Parity_No;
break;
}
if (stop_bits == 2) {
obj->stopbits = USART_StopBits_2;
}
else {
obj->stopbits = USART_StopBits_1;
}
USART_Cmd(usart, DISABLE);
USART_InitStructure.USART_BaudRate = obj->baudrate;
USART_InitStructure.USART_WordLength = obj->databits;
USART_InitStructure.USART_StopBits = obj->stopbits;
USART_InitStructure.USART_Parity = obj->parity;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(usart, &USART_InitStructure);
USART_Cmd(usart, ENABLE);
}
/******************************************************************************
* INTERRUPTS HANDLING
******************************************************************************/
// not api
void uart1_irq(void) {
USART_TypeDef *usart = (USART_TypeDef *)UART_1;
if (serial_irq_ids[0] != 0) {
if (USART_GetITStatus(usart, USART_IT_TXE) != RESET) {
irq_handler(serial_irq_ids[0], TxIrq);
}
if (USART_GetITStatus(usart, USART_IT_RXNE) != RESET) {
irq_handler(serial_irq_ids[0], RxIrq);
}
}
}
// not api
void uart2_irq(void) {
USART_TypeDef *usart = (USART_TypeDef *)UART_2;
if (serial_irq_ids[1] != 0) {
if (USART_GetITStatus(usart, USART_IT_TXE) != RESET) {
irq_handler(serial_irq_ids[1], TxIrq);
}
if (USART_GetITStatus(usart, USART_IT_RXNE) != RESET) {
irq_handler(serial_irq_ids[1], RxIrq);
}
}
}
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) {
irq_handler = handler;
serial_irq_ids[obj->index] = id;
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
IRQn_Type irq_n = (IRQn_Type)0;
uint32_t vector = 0;
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
if (obj->uart == UART_1) {
irq_n = USART1_IRQn;
vector = (uint32_t)&uart1_irq;
}
if (obj->uart == UART_2) {
irq_n = USART2_IRQn;
vector = (uint32_t)&uart2_irq;
}
if (enable) {
if (irq == RxIrq) {
USART_ITConfig(usart, USART_IT_RXNE, ENABLE);
}
else { // TxIrq
USART_ITConfig(usart, USART_IT_TXE, ENABLE);
}
NVIC_SetVector(irq_n, vector);
NVIC_EnableIRQ(irq_n);
} else { // disable
int all_disabled = 0;
if (irq == RxIrq) {
USART_ITConfig(usart, USART_IT_RXNE, DISABLE);
// Check if TxIrq is disabled too
if ((usart->CR1 & USART_CR1_TXEIE) == 0) all_disabled = 1;
}
else { // TxIrq
USART_ITConfig(usart, USART_IT_TXE, DISABLE);
// Check if RxIrq is disabled too
if ((usart->CR1 & USART_CR1_RXNEIE) == 0) all_disabled = 1;
}
if (all_disabled) NVIC_DisableIRQ(irq_n);
}
}
/******************************************************************************
* READ/WRITE
******************************************************************************/
int serial_getc(serial_t *obj) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
while (!serial_readable(obj));
return (int)(USART_ReceiveData(usart));
}
void serial_putc(serial_t *obj, int c) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
while (!serial_writable(obj));
USART_SendData(usart, (uint16_t)c);
}
int serial_readable(serial_t *obj) {
int status;
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
// Check if data is received
status = ((USART_GetFlagStatus(usart, USART_FLAG_RXNE) != RESET) ? 1 : 0);
return status;
}
int serial_writable(serial_t *obj) {
int status;
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
// Check if data is transmitted
status = ((USART_GetFlagStatus(usart, USART_FLAG_TXE) != RESET) ? 1 : 0);
return status;
}
void serial_clear(serial_t *obj) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
USART_ClearFlag(usart, USART_FLAG_TXE);
USART_ClearFlag(usart, USART_FLAG_RXNE);
}
void serial_pinout_tx(PinName tx) {
pinmap_pinout(tx, PinMap_UART_TX);
}
void serial_break_set(serial_t *obj) {
USART_TypeDef *usart = (USART_TypeDef *)(obj->uart);
USART_SendBreak(usart);
}
void serial_break_clear(serial_t *obj) {
}

View File

@ -0,0 +1,281 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
//==============================================================================
// STM32F103
//==============================================================================
#include "spi_api.h"
#if DEVICE_SPI
#include <math.h>
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
static const PinMap PinMap_SPI_MOSI[] = {
{PA_7, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 0)},
{PB_5, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 1)}, // Remap
{NC, NC, 0}
};
static const PinMap PinMap_SPI_MISO[] = {
{PA_6, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 0)},
{PB_4, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 1)}, // Remap
{NC, NC, 0}
};
static const PinMap PinMap_SPI_SCLK[] = {
{PA_5, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 0)},
{PB_3, SPI_1, STM_PIN_DATA(GPIO_Mode_AF_PP, 1)}, // Remap
{NC, NC, 0}
};
// Only used in Slave mode
static const PinMap PinMap_SPI_SSEL[] = {
{PA_4, SPI_1, STM_PIN_DATA(GPIO_Mode_IN_FLOATING, 0)},
{PA_15, SPI_1, STM_PIN_DATA(GPIO_Mode_IN_FLOATING, 1)}, // Remap
{NC, NC, 0}
};
void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) {
SPI_TypeDef *spi;
SPI_InitTypeDef SPI_InitStructure;
// Determine the SPI to use
SPIName spi_mosi = (SPIName)pinmap_peripheral(mosi, PinMap_SPI_MOSI);
SPIName spi_miso = (SPIName)pinmap_peripheral(miso, PinMap_SPI_MISO);
SPIName spi_sclk = (SPIName)pinmap_peripheral(sclk, PinMap_SPI_SCLK);
SPIName spi_ssel = (SPIName)pinmap_peripheral(ssel, PinMap_SPI_SSEL);
SPIName spi_data = (SPIName)pinmap_merge(spi_mosi, spi_miso);
SPIName spi_cntl = (SPIName)pinmap_merge(spi_sclk, spi_ssel);
obj->spi = (SPIName)pinmap_merge(spi_data, spi_cntl);
if (obj->spi == (SPIName)NC) {
error("SPI pinout mapping failed");
}
// Get SPI registers structure address
spi = (SPI_TypeDef *)(obj->spi);
// Enable SPI clock
if (obj->spi == SPI_1) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
}
if (obj->spi == SPI_2) {
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
}
// Configure the SPI pins
pinmap_pinout(mosi, PinMap_SPI_MOSI);
pinmap_pinout(miso, PinMap_SPI_MISO);
pinmap_pinout(sclk, PinMap_SPI_SCLK);
// Save new values
obj->bits = SPI_DataSize_8b;
obj->cpol = SPI_CPOL_Low;
obj->cpha = SPI_CPHA_1Edge;
obj->br_presc = SPI_BaudRatePrescaler_64; // Closest to 1MHz (72MHz/64 = 1.125MHz)
if (ssel == NC) { // Master
obj->mode = SPI_Mode_Master;
obj->nss = SPI_NSS_Soft;
}
else { // Slave
pinmap_pinout(ssel, PinMap_SPI_SSEL);
obj->mode = SPI_Mode_Slave;
obj->nss = SPI_NSS_Hard;
}
// SPI configuration
SPI_InitStructure.SPI_Mode = obj->mode;
SPI_InitStructure.SPI_NSS = obj->nss;
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_DataSize = obj->bits;
SPI_InitStructure.SPI_CPOL = obj->cpol;
SPI_InitStructure.SPI_CPHA = obj->cpha;
SPI_InitStructure.SPI_BaudRatePrescaler = obj->br_presc;
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(spi, &SPI_InitStructure);
SPI_Cmd(spi, ENABLE);
}
void spi_free(spi_t *obj) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
SPI_I2S_DeInit(spi);
}
void spi_format(spi_t *obj, int bits, int mode, int slave) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
SPI_InitTypeDef SPI_InitStructure;
// Save new values
if (bits == 8) {
obj->bits = SPI_DataSize_8b;
}
else {
obj->bits = SPI_DataSize_16b;
}
switch (mode) {
case 0:
obj->cpol = SPI_CPOL_Low;
obj->cpha = SPI_CPHA_1Edge;
break;
case 1:
obj->cpol = SPI_CPOL_Low;
obj->cpha = SPI_CPHA_2Edge;
break;
case 2:
obj->cpol = SPI_CPOL_High;
obj->cpha = SPI_CPHA_1Edge;
break;
default:
obj->cpol = SPI_CPOL_High;
obj->cpha = SPI_CPHA_2Edge;
break;
}
if (slave == 0) {
obj->mode = SPI_Mode_Master;
obj->nss = SPI_NSS_Soft;
}
else {
obj->mode = SPI_Mode_Slave;
obj->nss = SPI_NSS_Hard;
}
SPI_Cmd(spi, DISABLE);
SPI_InitStructure.SPI_Mode = obj->mode;
SPI_InitStructure.SPI_NSS = obj->nss;
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_DataSize = obj->bits;
SPI_InitStructure.SPI_CPOL = obj->cpol;
SPI_InitStructure.SPI_CPHA = obj->cpha;
SPI_InitStructure.SPI_BaudRatePrescaler = obj->br_presc;
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(spi, &SPI_InitStructure);
SPI_Cmd(spi, ENABLE);
}
void spi_frequency(spi_t *obj, int hz) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
SPI_InitTypeDef SPI_InitStructure;
// Get SPI clock frequency
uint32_t PCLK = SystemCoreClock >> 1;
// Choose the baud rate divisor (between 2 and 256)
uint32_t divisor = PCLK / hz;
// Find the nearest power-of-2
divisor = (divisor > 0 ? divisor-1 : 0);
divisor |= divisor >> 1;
divisor |= divisor >> 2;
divisor |= divisor >> 4;
divisor |= divisor >> 8;
divisor |= divisor >> 16;
divisor++;
uint32_t baud_rate = __builtin_ffs(divisor) - 2;
// Save new value
obj->br_presc = ((baud_rate > 7) ? (7 << 3) : (baud_rate << 3));
SPI_Cmd(spi, DISABLE);
SPI_InitStructure.SPI_Mode = obj->mode;
SPI_InitStructure.SPI_NSS = obj->nss;
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_DataSize = obj->bits;
SPI_InitStructure.SPI_CPOL = obj->cpol;
SPI_InitStructure.SPI_CPHA = obj->cpha;
SPI_InitStructure.SPI_BaudRatePrescaler = obj->br_presc;
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(spi, &SPI_InitStructure);
SPI_Cmd(spi, ENABLE);
}
static inline int ssp_readable(spi_t *obj) {
int status;
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
// Check if data is received
status = ((SPI_I2S_GetFlagStatus(spi, SPI_I2S_FLAG_RXNE) != RESET) ? 1 : 0);
return status;
}
static inline int ssp_writeable(spi_t *obj) {
int status;
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
// Check if data is transmitted
status = ((SPI_I2S_GetFlagStatus(spi, SPI_I2S_FLAG_TXE) != RESET) ? 1 : 0);
return status;
}
static inline void ssp_write(spi_t *obj, int value) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
while (!ssp_writeable(obj));
SPI_I2S_SendData(spi, (uint16_t)value);
}
static inline int ssp_read(spi_t *obj) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
while (!ssp_readable(obj));
return (int)SPI_I2S_ReceiveData(spi);
}
static inline int ssp_busy(spi_t *obj) {
int status;
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
status = ((SPI_I2S_GetFlagStatus(spi, SPI_I2S_FLAG_BSY) != RESET) ? 1 : 0);
return status;
}
int spi_master_write(spi_t *obj, int value) {
ssp_write(obj, value);
return ssp_read(obj);
}
int spi_slave_receive(spi_t *obj) {
return (ssp_readable(obj) && !ssp_busy(obj)) ? (1) : (0);
};
int spi_slave_read(spi_t *obj) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
return (int)SPI_I2S_ReceiveData(spi);
}
void spi_slave_write(spi_t *obj, int value) {
SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi);
while (!ssp_writeable(obj));
SPI_I2S_SendData(spi, (uint16_t)value);
}
int spi_busy(spi_t *obj) {
return ssp_busy(obj);
}
#endif