added black F4 variant files + activated USB interface

This commit is contained in:
stevstrong 2017-04-14 19:26:18 +02:00
parent 3d775ac3c5
commit 065f58684d
21 changed files with 4084 additions and 0 deletions

View File

@ -0,0 +1,241 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Michael Hope.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#ifdef STM32F4
/**
* @file dmaF4.c
* @brief Direct Memory Access peripheral support
*/
#include "dma.h"
#include "bitband.h"
#include "util.h"
/*
* Devices
*/
static dma_dev dma1 = {
.regs = DMA1_BASE,
.clk_id = RCC_DMA1,
.handlers = {{ .handler = NULL, .irq_line = 11 },
{ .handler = NULL, .irq_line = 12 },
{ .handler = NULL, .irq_line = 13 },
{ .handler = NULL, .irq_line = 14 },
{ .handler = NULL, .irq_line = 15 },
{ .handler = NULL, .irq_line = 16 },
{ .handler = NULL, .irq_line = 17 },
{ .handler = NULL, .irq_line = 47 }}
};
/** DMA1 device */
dma_dev *DMA1 = &dma1;
static dma_dev dma2 = {
.regs = DMA2_BASE,
.clk_id = RCC_DMA2,
.handlers = {{ .handler = NULL, .irq_line = 56 },
{ .handler = NULL, .irq_line = 57 },
{ .handler = NULL, .irq_line = 58 },
{ .handler = NULL, .irq_line = 59 },
{ .handler = NULL, .irq_line = 60 },
{ .handler = NULL, .irq_line = 68 },
{ .handler = NULL, .irq_line = 69 },
{ .handler = NULL, .irq_line = 70 }} /* !@#$ */
};
/** DMA2 device */
dma_dev *DMA2 = &dma2;
/*
* Convenience routines
*/
/**
* @brief Initialize a DMA device.
* @param dev Device to initialize.
*/
void dma_init(dma_dev *dev) {
rcc_clk_enable(dev->clk_id);
}
/**
* @brief Attach an interrupt to a DMA transfer.
*
* Interrupts are enabled using appropriate mode flags in
* dma_setup_transfer().
*
* @param dev DMA device
* @param stream Stream to attach handler to
* @param handler Interrupt handler to call when channel interrupt fires.
* @see dma_setup_transfer()
* @see dma_detach_interrupt()
*/
void dma_attach_interrupt(dma_dev *dev,
dma_stream stream,
void (*handler)(void)) {
dev->handlers[stream].handler = handler;
nvic_irq_enable(dev->handlers[stream].irq_line);
}
/**
* @brief Detach a DMA transfer interrupt handler.
*
* After calling this function, the given channel's interrupts will be
* disabled.
*
* @param dev DMA device
* @param stream Stream whose handler to detach
* @sideeffect Clears interrupt enable bits in the channel's CCR register.
* @see dma_attach_interrupt()
*/
void dma_detach_interrupt(dma_dev *dev, dma_stream stream) {
nvic_irq_disable(dev->handlers[stream].irq_line);
dev->handlers[stream].handler = NULL;
}
void dma_clear_isr_bits(dma_dev *dev, dma_stream stream) {
switch (stream) {
case 0:
dev->regs->LIFCR|=0x0000003d;
break;
case 1:
dev->regs->LIFCR|=0x00000f40;
break;
case 2:
dev->regs->LIFCR|=0x003d0000;
break;
case 3:
dev->regs->LIFCR|=0x0f400000;
break;
case 4:
dev->regs->HIFCR|=0x0000003d;
break;
case 5:
dev->regs->HIFCR|=0x00000f40;
break;
case 6:
dev->regs->HIFCR|=0x003d0000;
break;
case 7:
dev->regs->HIFCR|=0x0f400000;
break;
}
}
/*
* IRQ handlers
*/
static inline void dispatch_handler(dma_dev *dev, dma_stream stream) {
void (*handler)(void) = dev->handlers[stream].handler;
if (handler) {
handler();
dma_clear_isr_bits(dev, stream); /* in case handler doesn't */
}
}
//void __irq_dma1_stream0(void) {
void __irq_dma1_channel1(void) {
dispatch_handler(DMA1, DMA_STREAM0);
}
//void __irq_dma1_stream1(void) {
void __irq_dma1_channel2(void) {
dispatch_handler(DMA1, DMA_STREAM1);
}
//void __irq_dma1_stream2(void) {
void __irq_dma1_channel3(void) {
dispatch_handler(DMA1, DMA_STREAM2);
}
//void __irq_dma1_stream3(void) {
void __irq_dma1_channel4(void) {
dispatch_handler(DMA1, DMA_STREAM3);
}
//void __irq_dma1_stream4(void) {
void __irq_dma1_channel5(void) {
dispatch_handler(DMA1, DMA_STREAM4);
}
//void __irq_dma1_stream5(void) {
void __irq_dma1_channel6(void) {
dispatch_handler(DMA1, DMA_STREAM5);
}
//void __irq_dma1_stream6(void) {
void __irq_dma1_channel7(void) {
dispatch_handler(DMA1, DMA_STREAM6);
}
//void __irq_dma1_stream7(void) {
void __irq_adc3(void) {
dispatch_handler(DMA1, DMA_STREAM7);
}
//void __irq_dma2_stream0(void) {
void __irq_dma2_channel1(void) {
dispatch_handler(DMA2, DMA_STREAM0);
}
//void __irq_dma2_stream1(void) {
void __irq_dma2_channel2(void) {
dispatch_handler(DMA2, DMA_STREAM1);
}
//void __irq_dma2_stream2(void) {
void __irq_dma2_channel3(void) {
dispatch_handler(DMA2, DMA_STREAM2);
}
//void __irq_dma2_stream3(void) {
void __irq_dma2_channel4_5(void) {
dispatch_handler(DMA2, DMA_STREAM3);
}
//void __irq_dma2_stream4(void) {
void __irq_DMA2_Stream4_IRQHandler(void) {
dispatch_handler(DMA2, DMA_STREAM4);
}
//void __irq_dma2_stream5(void) {
void __irq_DMA2_Stream5_IRQHandler(void) {
dispatch_handler(DMA2, DMA_STREAM5);
}
//void __irq_dma2_stream6(void) {
void __irq_DMA2_Stream6_IRQHandler(void) {
dispatch_handler(DMA2, DMA_STREAM6);
}
//void __irq_dma2_stream7(void) {
void __irq_DMA2_Stream7_IRQHandler(void) {
dispatch_handler(DMA2, DMA_STREAM7);
}
#endif

View File

@ -0,0 +1,270 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Michael Hope.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file dma.h
*
* @author Marti Bolivar <mbolivar@leaflabs.com>;
* Original implementation by Michael Hope
*
* @brief Direct Memory Access peripheral support
*/
/*
* See /notes/dma.txt for more information.
*/
#ifndef _DMA_H_
#define _DMA_H_
#include "libmaple_types.h"
#include "rcc.h"
#include "nvic.h"
#ifdef __cplusplus
extern "C"{
#endif
/*
* Register maps
*/
/**
* @brief DMA stream type.
*
*/
typedef struct dma_stream_t {
__io uint32 CR; /**< Stream configuration register */
__io uint32 NDTR; /**< Stream number of data register */
__io uint32 PAR; /**< Stream peripheral address register */
__io uint32 M0AR; /**< Stream memory address register 0 */
__io uint32 M1AR; /**< Stream memory address register 1 */
__io uint32 FCR; /**< Stream FIFO configuration register */
} dma_stream_t;
/**
* @brief DMA register map type.
*
*/
typedef struct dma_reg_map {
__io uint32 LISR; /**< Low interrupt status register */
__io uint32 HISR; /**< High interrupt status register */
__io uint32 LIFCR; /**< Low interrupt flag clear register */
__io uint32 HIFCR; /**< High interrupt flag clear register */
dma_stream_t STREAM[8];
} dma_reg_map;
/** DMA controller register map base pointers */
#define DMA1_BASE ((struct dma_reg_map*)0x40026000)
#define DMA2_BASE ((struct dma_reg_map*)0x40026400)
/*
* Register bit definitions
*/
/* Channel configuration register */
#define DMA_CR_CH0 (0x0 << 25)
#define DMA_CR_CH1 (0x1 << 25)
#define DMA_CR_CH2 (0x2 << 25)
#define DMA_CR_CH3 (0x3 << 25)
#define DMA_CR_CH4 (0x4 << 25)
#define DMA_CR_CH5 (0x5 << 25)
#define DMA_CR_CH6 (0x6 << 25)
#define DMA_CR_CH7 (0x7 << 25)
#define DMA_CR_MBURST0 (0x0 << 23)
#define DMA_CR_MBURST4 (0x1 << 23)
#define DMA_CR_MBURST8 (0x2 << 23)
#define DMA_CR_MBURST16 (0x3 << 23)
#define DMA_CR_PBURST0 (0x0 << 21)
#define DMA_CR_PBURST4 (0x1 << 21)
#define DMA_CR_PBURST8 (0x2 << 21)
#define DMA_CR_PBURST16 (0x3 << 21)
#define DMA_CR_CT0 (0x0 << 19)
#define DMA_CR_CT1 (0x1 << 19)
#define DMA_CR_DBM (0x1 << 18)
#define DMA_CR_PL_LOW (0x0 << 16)
#define DMA_CR_PL_MEDIUM (0x1 << 16)
#define DMA_CR_PL_HIGH (0x2 << 16)
#define DMA_CR_PL_VERY_HIGH (0x3 << 16)
#define DMA_CR_PL_MASK (0x3 << 16)
#define DMA_CR_PINCOS (0x1 << 15)
#define DMA_CR_MSIZE_8BITS (0x0 << 13)
#define DMA_CR_MSIZE_16BITS (0x1 << 13)
#define DMA_CR_MSIZE_32BITS (0x2 << 13)
#define DMA_CR_PSIZE_8BITS (0x0 << 11)
#define DMA_CR_PSIZE_16BITS (0x1 << 11)
#define DMA_CR_PSIZE_32BITS (0x2 << 11)
#define DMA_CR_MINC (0x1 << 10)
#define DMA_CR_PINC (0x1 << 9)
#define DMA_CR_CIRC (0x1 << 8)
#define DMA_CR_DIR_P2M (0x0 << 6)
#define DMA_CR_DIR_M2P (0x1 << 6)
#define DMA_CR_DIR_M2M (0x2 << 6)
#define DMA_CR_PFCTRL (0x1 << 5)
#define DMA_CR_TCIE (0x1 << 4)
#define DMA_CR_HTIE (0x1 << 3)
#define DMA_CR_TEIE (0x1 << 2)
#define DMA_CR_DMEIE (0x1 << 1)
#define DMA_CR_EN (0x1)
/*
* Devices
*/
/** Encapsulates state related to a DMA channel interrupt. */
typedef struct dma_handler_config {
void (*handler)(void); /**< User-specified channel interrupt
handler */
nvic_irq_num irq_line; /**< Channel's NVIC interrupt number */
} dma_handler_config;
/** DMA device type */
typedef struct dma_dev {
dma_reg_map *regs; /**< Register map */
rcc_clk_id clk_id; /**< Clock ID */
dma_handler_config handlers[]; /**<
* @brief IRQ handlers and NVIC numbers.
*
* @see dma_attach_interrupt()
* @see dma_detach_interrupt()
*/
} dma_dev;
extern dma_dev *DMA1;
extern dma_dev *DMA2;
/*
* Convenience functions
*/
void dma_init(dma_dev *dev);
/** Flags for DMA transfer configuration. */
typedef enum dma_mode_flags {
DMA_MEM_2_MEM = 1 << 14, /**< Memory to memory mode */
DMA_MINC_MODE = 1 << 7, /**< Auto-increment memory address */
DMA_PINC_MODE = 1 << 6, /**< Auto-increment peripheral address */
DMA_CIRC_MODE = 1 << 5, /**< Circular mode */
DMA_FROM_MEM = 1 << 4, /**< Read from memory to peripheral */
DMA_TRNS_ERR = 1 << 3, /**< Interrupt on transfer error */
DMA_HALF_TRNS = 1 << 2, /**< Interrupt on half-transfer */
DMA_TRNS_CMPLT = 1 << 1 /**< Interrupt on transfer completion */
} dma_mode_flags;
/** Source and destination transfer sizes. */
typedef enum dma_xfer_size {
DMA_SIZE_8BITS = 0, /**< 8-bit transfers */
DMA_SIZE_16BITS = 1, /**< 16-bit transfers */
DMA_SIZE_32BITS = 2 /**< 32-bit transfers */
} dma_xfer_size;
/** DMA channel */
typedef enum dma_stream {
DMA_STREAM0 = 0, /**< Stream 0 */
DMA_STREAM1 = 1, /**< Stream 1 */
DMA_STREAM2 = 2, /**< Stream 2 */
DMA_STREAM3 = 3, /**< Stream 3 */
DMA_STREAM4 = 4, /**< Stream 4 */
DMA_STREAM5 = 5, /**< Stream 5 */
DMA_STREAM6 = 6, /**< Stream 6 */
DMA_STREAM7 = 7, /**< Stream 7 */
} dma_stream;
static inline void dma_setup_transfer(dma_dev *dev,
dma_stream stream,
__io void *peripheral_address,
__io void *memory_address0,
__io void *memory_address1,
uint32 flags,
uint32 fifo_flags) {
dev->regs->STREAM[stream].CR &= ~DMA_CR_EN; // disable
dev->regs->STREAM[stream].PAR = (uint32)peripheral_address;
dev->regs->STREAM[stream].M0AR = (uint32)memory_address0;
dev->regs->STREAM[stream].M1AR = (uint32)memory_address1;
dev->regs->STREAM[stream].FCR = fifo_flags & 0x87; // mask out reserved bits
dev->regs->STREAM[stream].CR = flags & 0x0feffffe; // mask out reserved and enable
}
static inline void dma_set_num_transfers(dma_dev *dev,
dma_stream stream,
uint16 num_transfers) {
dev->regs->STREAM[stream].NDTR = num_transfers;
}
void dma_attach_interrupt(dma_dev *dev,
dma_stream stream,
void (*handler)(void));
void dma_detach_interrupt(dma_dev *dev, dma_stream stream);
static inline void dma_enable(dma_dev *dev, dma_stream stream) {
dev->regs->STREAM[stream].CR |= DMA_CR_EN;
}
static inline void dma_disable(dma_dev *dev, dma_stream stream) {
dev->regs->STREAM[stream].CR &= ~DMA_CR_EN;
}
/**
* @brief Check if a DMA stream is enabled
* @param dev DMA device
* @param stream Stream whose enabled bit to check.
*/
static inline uint8 dma_is_stream_enabled(dma_dev *dev, dma_stream stream) {
return (uint8)(dev->regs->STREAM[stream].CR & DMA_CR_EN);
}
/**
* @brief Get the ISR status bits for a DMA stream.
*
* The bits are returned right-aligned, in the following order:
* transfer error flag, half-transfer flag, transfer complete flag,
* global interrupt flag.
*
* @param dev DMA device
* @param stream Stream whose ISR bits to return.
*/
uint8 dma_get_isr_bits(dma_dev *dev, dma_stream stream);
/**
* @brief Clear the ISR status bits for a given DMA stream.
*
* @param dev DMA device
* @param stream Stream whose ISR bits to clear.
*/
void dma_clear_isr_bits(dma_dev *dev, dma_stream stream);
#ifdef __cplusplus
} // extern "C"
#endif
#endif

View File

@ -0,0 +1,224 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#ifdef STM32F4
/**
* @file gpio.c
* @brief GPIO initialization routine
*/
#include "gpio.h"
#include "rcc.h"
/*
* GPIO devices
*/
gpio_dev gpioa = {
.regs = GPIOA_BASE,
.clk_id = RCC_GPIOA,
.exti_port = AFIO_EXTI_PA,
};
/** GPIO port A device. */
gpio_dev* const GPIOA = &gpioa;
gpio_dev gpiob = {
.regs = GPIOB_BASE,
.clk_id = RCC_GPIOB,
.exti_port = AFIO_EXTI_PB,
};
/** GPIO port B device. */
gpio_dev* const GPIOB = &gpiob;
gpio_dev gpioc = {
.regs = GPIOC_BASE,
.clk_id = RCC_GPIOC,
.exti_port = AFIO_EXTI_PC,
};
/** GPIO port C device. */
gpio_dev* const GPIOC = &gpioc;
gpio_dev gpiod = {
.regs = GPIOD_BASE,
.clk_id = RCC_GPIOD,
.exti_port = AFIO_EXTI_PD,
};
/** GPIO port D device. */
gpio_dev* const GPIOD = &gpiod;
#ifdef STM32_HIGH_DENSITY
gpio_dev gpioe = {
.regs = GPIOE_BASE,
.clk_id = RCC_GPIOE,
.exti_port = AFIO_EXTI_PE,
};
/** GPIO port E device. */
gpio_dev* const GPIOE = &gpioe;
gpio_dev gpiof = {
.regs = GPIOF_BASE,
.clk_id = RCC_GPIOF,
.exti_port = AFIO_EXTI_PF,
};
/** GPIO port F device. */
gpio_dev* const GPIOF = &gpiof;
gpio_dev gpiog = {
.regs = GPIOG_BASE,
.clk_id = RCC_GPIOG,
.exti_port = AFIO_EXTI_PG,
};
/** GPIO port G device. */
gpio_dev* const GPIOG = &gpiog;
#endif
/*
* GPIO convenience routines
*/
/**
* Initialize a GPIO device.
*
* Enables the clock for and resets the given device.
*
* @param dev GPIO device to initialize.
*/
void gpio_init(gpio_dev *dev) {
rcc_clk_enable(dev->clk_id);
rcc_reset_dev(dev->clk_id);
}
/**
* Initialize and reset all available GPIO devices.
*/
void gpio_init_all(void) {
gpio_init(GPIOA);
gpio_init(GPIOB);
gpio_init(GPIOC);
gpio_init(GPIOD);
#ifdef STM32_HIGH_DENSITY
gpio_init(GPIOE);
gpio_init(GPIOF);
gpio_init(GPIOG);
#endif
#ifdef ARDUINO_STM32F4_NETDUINO2PLUS
// PA8 Output the Master Clock MCO1
gpio_set_af_mode(GPIOA, 8, 0);
gpio_set_mode(GPIOA, 8, GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
// PB4 as alternate MISO Input
gpio_set_af_mode(GPIOB, 4, 5);
// PA5 as alternate SCK Output
gpio_set_af_mode(GPIOA, 5, 5);
// PA7 as alternate MOSI Output
gpio_set_af_mode(GPIOA, 7, 5);
#endif
}
/**
* Set the mode of a GPIO pin.
*
* @param dev GPIO device.
* @param pin Pin on the device whose mode to set, 0--15.
* @param mode General purpose or alternate function mode to set the pin to.
* @see gpio_pin_mode
*/
void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode) {
gpio_reg_map *regs = dev->regs;
//regs->AFR[pin/8] = (regs->AFR[pin/8] & ~(15 << (4*(pin&7)))) | (((mode >> 8) & 15) << (4*(pin&7)));
//gpio_set_af_mode(dev, pin, mode>>8);
regs->MODER = (regs->MODER & ~( 3 << (2*pin))) | (((mode >> 0) & 3) << (2*pin));
regs->PUPDR = (regs->PUPDR & ~( 3 << (2*pin))) | (((mode >> 2) & 3) << (2*pin));
regs->OSPEEDR = (regs->OSPEEDR & ~( 3 << (2*pin))) | (((mode >> 4) & 3) << (2*pin));
regs->OTYPER = (regs->OTYPER & ~( 1 << (1*pin))) | (((mode >> 6) & 1) << (1*pin));
}
/**
* Set the alternate function mode of a GPIO pin.
*
* @param dev GPIO device.
* @param pin Pin on the device whose mode to set, 0--15.
* @param mode alternate function mode to set the pin to.
* @see gpio_pin_mode
*/
void gpio_set_af_mode(gpio_dev *dev, uint8 pin, int mode) {
gpio_reg_map *regs = dev->regs;
regs->AFR[pin/8] = (regs->AFR[pin/8] & ~(15 << (4*(pin&7)))) | (((mode >> 0) & 15) << (4*(pin&7)));
}
/*
* AFIO
*/
/**
* @brief Initialize the AFIO clock, and reset the AFIO registers.
*/
void afio_init(void) {
//rcc_clk_enable(RCC_AFIO);
//rcc_reset_dev(RCC_AFIO);
}
#define AFIO_EXTI_SEL_MASK 0xF
/**
* @brief Select a source input for an external interrupt.
*
* @param exti External interrupt.
* @param gpio_port Port which contains pin to use as source input.
* @see afio_exti_num
* @see afio_exti_port
*/
void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port) {
__io uint32 *exti_cr = &SYSCFG_BASE->EXTICR1 + exti / 4;
uint32 shift = 4 * (exti % 4);
uint32 cr = *exti_cr;
cr &= ~(AFIO_EXTI_SEL_MASK << shift);
cr |= gpio_port << shift;
*exti_cr = cr;
}
/**
* @brief Perform an alternate function remap.
* @param remapping Remapping to perform.
*/
#if 0
void afio_remap(afio_remap_peripheral remapping) {
if (remapping & AFIO_REMAP_USE_MAPR2) {
remapping &= ~AFIO_REMAP_USE_MAPR2;
AFIO_BASE->MAPR2 |= remapping;
} else {
AFIO_BASE->MAPR |= remapping;
}
}
#endif
#endif

View File

@ -0,0 +1,550 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file gpio.h
*
* @brief General purpose I/O (GPIO) and Alternate Function I/O
* (AFIO) prototypes, defines, and inlined access functions.
*/
#ifndef _GPIO_H_
#define _GPIO_H_
#include "libmaple.h"
#include "rcc.h"
#ifdef __cplusplus
extern "C"{
#endif
/*
* GPIO register maps and devices
*/
/** GPIO register map type */
typedef struct gpio_reg_map {
__io uint32 MODER; /*!< GPIO port mode register, Address offset: 0x00 */
__io uint32 OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */
__io uint32 OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */
__io uint32 PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */
__io uint32 IDR; /*!< GPIO port input data register, Address offset: 0x10 */
__io uint32 ODR; /*!< GPIO port output data register, Address offset: 0x14 */
__io uint16 BSRRL; /*!< GPIO port bit set/reset low register, Address offset: 0x18 */
__io uint16 BSRRH; /*!< GPIO port bit set/reset high register, Address offset: 0x1A */
__io uint32 LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */
__io uint32 AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x24-0x28 */
} gpio_reg_map;
/**
* @brief External interrupt line port selector.
*
* Used to determine which GPIO port to map an external interrupt line
* onto. */
/* (See AFIO sections, below) */
typedef enum afio_exti_port {
AFIO_EXTI_PA, /**< Use port A (PAx) pin. */
AFIO_EXTI_PB, /**< Use port B (PBx) pin. */
AFIO_EXTI_PC, /**< Use port C (PCx) pin. */
AFIO_EXTI_PD, /**< Use port D (PDx) pin. */
#ifdef STM32_HIGH_DENSITY
AFIO_EXTI_PE, /**< Use port E (PEx) pin. */
AFIO_EXTI_PF, /**< Use port F (PFx) pin. */
AFIO_EXTI_PG, /**< Use port G (PGx) pin. */
#endif
} afio_exti_port;
/** GPIO device type */
typedef struct gpio_dev {
gpio_reg_map *regs; /**< Register map */
rcc_clk_id clk_id; /**< RCC clock information */
afio_exti_port exti_port; /**< AFIO external interrupt port value */
} gpio_dev;
extern gpio_dev gpioa;
extern gpio_dev* const GPIOA;
extern gpio_dev gpiob;
extern gpio_dev* const GPIOB;
extern gpio_dev gpioc;
extern gpio_dev* const GPIOC;
extern gpio_dev gpiod;
extern gpio_dev* const GPIOD;
#ifdef STM32_HIGH_DENSITY
extern gpio_dev gpioe;
extern gpio_dev* const GPIOE;
extern gpio_dev gpiof;
extern gpio_dev* const GPIOF;
extern gpio_dev gpiog;
extern gpio_dev* const GPIOG;
#endif
/** GPIO port register map base pointer */
#define GPIOA_BASE ((struct gpio_reg_map*)0x40020000)
#define GPIOB_BASE ((struct gpio_reg_map*)0x40020400)
#define GPIOC_BASE ((struct gpio_reg_map*)0x40020800)
#define GPIOD_BASE ((struct gpio_reg_map*)0x40020C00)
#ifdef STM32_HIGH_DENSITY
#define GPIOE_BASE ((struct gpio_reg_map*)0x40021000)
#define GPIOF_BASE ((struct gpio_reg_map*)0x40021400)
#define GPIOG_BASE ((struct gpio_reg_map*)0x40021800)
#endif
/*
* GPIO register bit definitions
*/
#define GPIO_MODE_INPUT 0
#define GPIO_MODE_OUTPUT 1
#define GPIO_MODE_AF 2
#define GPIO_MODE_ANALOG 3
#define GPIO_PUPD_INPUT_FLOATING (0 << 2)
#define GPIO_PUPD_INPUT_PU (1 << 2)
#define GPIO_PUPD_INPUT_PD (2 << 2)
#define GPIO_OSPEED_2MHZ (0 << 4)
#define GPIO_OSPEED_25MHZ (1 << 4)
#define GPIO_OSPEED_50MHZ (2 << 4)
#define GPIO_OSPEED_100MHZ (3 << 4)
#define GPIO_OTYPE_PP (0 << 6)
#define GPIO_OTYPE_OD (1 << 6)
/*
MODER
00: Input (reset state)
01: General purpose output mode
10: Alternate function mode
11: Analog mode
OTYPER
0: Output push-pull (reset state)
1: Output open-drain
OSPEEDR
00: 2 MHz Low speed
01: 25 MHz Medium speed
10: 50 MHz Fast speed
11: 100 MHz High speed on 30 pF (80 MHz Output max speed on 15 pF)
PUPDR
00: No pull-up, pull-down
01: Pull-up
10: Pull-down
AFRL 4 bit AF00-AF15
AFRH 4 bit AF00-AF15
*/
/**
* @brief GPIO Pin modes.
*
* These only allow for 50MHZ max output speeds; if you want slower,
* use direct register access.
*/
typedef enum gpio_pin_mode {
GPIO_OUTPUT_PP = (GPIO_MODE_OUTPUT | GPIO_OTYPE_PP |
GPIO_OSPEED_50MHZ), /**< Output push-pull. */
GPIO_OUTPUT_OD = (GPIO_MODE_OUTPUT | GPIO_OTYPE_OD |
GPIO_OSPEED_50MHZ), /**< Output open-drain. */
GPIO_AF_OUTPUT_PP = (GPIO_MODE_AF | GPIO_OTYPE_PP |
GPIO_OSPEED_50MHZ), /**< Alternate function
output push-pull. */
GPIO_AF_OUTPUT_OD = (GPIO_MODE_AF | GPIO_OTYPE_OD |
GPIO_OSPEED_50MHZ), /**< Alternate function
output open drain. */
GPIO_INPUT_ANALOG = (GPIO_MODE_ANALOG), /**< Analog input. */
GPIO_INPUT_FLOATING = (GPIO_MODE_INPUT |
GPIO_PUPD_INPUT_FLOATING), /**< Input floating. */
GPIO_INPUT_PD = (GPIO_MODE_INPUT |
GPIO_PUPD_INPUT_PD), /**< Input pull-down. */
GPIO_INPUT_PU = (GPIO_MODE_INPUT |
GPIO_PUPD_INPUT_PU), /**< Input pull-up. */
GPIO_AF_INPUT_PD = (GPIO_MODE_AF |
GPIO_PUPD_INPUT_PD), /**< Input pull-down. */
GPIO_BIGNUMBER = 0xfff
} gpio_pin_mode;
/*
* GPIO Convenience routines
*/
void gpio_init(gpio_dev *dev);
void gpio_init_all(void);
void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode);
void gpio_set_af_mode(gpio_dev *dev, uint8 pin, int mode);
/**
* @brief Get a GPIO port's corresponding afio_exti_port.
* @param dev GPIO device whose afio_exti_port to return.
*/
static inline afio_exti_port gpio_exti_port(gpio_dev *dev) {
return dev->exti_port;
}
/**
* Set or reset a GPIO pin.
*
* Pin must have previously been configured to output mode.
*
* @param dev GPIO device whose pin to set.
* @param pin Pin on to set or reset
* @param val If true, set the pin. If false, reset the pin.
*/
static inline void gpio_write_bit(gpio_dev *dev, uint8 pin, uint8 val) {
if (val) {
dev->regs->BSRRL = BIT(pin);
} else {
dev->regs->BSRRH = BIT(pin);
}
}
/**
* Determine whether or not a GPIO pin is set.
*
* Pin must have previously been configured to input mode.
*
* @param dev GPIO device whose pin to test.
* @param pin Pin on dev to test.
* @return True if the pin is set, false otherwise.
*/
static inline uint32 gpio_read_bit(gpio_dev *dev, uint8 pin) {
return dev->regs->IDR & BIT(pin);
}
/**
* Toggle a pin configured as output push-pull.
* @param dev GPIO device.
* @param pin Pin on dev to toggle.
*/
static inline void gpio_toggle_bit(gpio_dev *dev, uint8 pin) {
dev->regs->ODR = dev->regs->ODR ^ BIT(pin);
}
/*
* AFIO register map
*/
/** AFIO register map */
typedef struct syscfg_reg_map {
__io uint32 MEMRM; /**< memory remap register */
__io uint32 PMC; /**< peripheral mode configuration register */
__io uint32 EXTICR1; /**< External interrupt configuration register 1. */
__io uint32 EXTICR2; /**< External interrupt configuration register 2. */
__io uint32 EXTICR3; /**< External interrupt configuration register 3. */
__io uint32 EXTICR4; /**< External interrupt configuration register 4. */
__io uint32 CMPCR; /**< Compensation cell control register */
} syscfg_reg_map;
/** AFIO register map base pointer. */
#define SYSCFG_BASE ((struct syscfg_reg_map *)0x40013800)
/*
* AFIO register bit definitions
*/
/* Event control register */
#define AFIO_EVCR_EVOE (0x1 << 7)
#define AFIO_EVCR_PORT_PA (0x0 << 4)
#define AFIO_EVCR_PORT_PB (0x1 << 4)
#define AFIO_EVCR_PORT_PC (0x2 << 4)
#define AFIO_EVCR_PORT_PD (0x3 << 4)
#define AFIO_EVCR_PORT_PE (0x4 << 4)
#define AFIO_EVCR_PIN_0 0x0
#define AFIO_EVCR_PIN_1 0x1
#define AFIO_EVCR_PIN_2 0x2
#define AFIO_EVCR_PIN_3 0x3
#define AFIO_EVCR_PIN_4 0x4
#define AFIO_EVCR_PIN_5 0x5
#define AFIO_EVCR_PIN_6 0x6
#define AFIO_EVCR_PIN_7 0x7
#define AFIO_EVCR_PIN_8 0x8
#define AFIO_EVCR_PIN_9 0x9
#define AFIO_EVCR_PIN_10 0xA
#define AFIO_EVCR_PIN_11 0xB
#define AFIO_EVCR_PIN_12 0xC
#define AFIO_EVCR_PIN_13 0xD
#define AFIO_EVCR_PIN_14 0xE
#define AFIO_EVCR_PIN_15 0xF
/* AF remap and debug I/O configuration register */
#define AFIO_MAPR_SWJ_CFG (0x7 << 24)
#define AFIO_MAPR_SWJ_CFG_FULL_SWJ (0x0 << 24)
#define AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST (0x1 << 24)
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW (0x4 << 24)
#define AFIO_MAPR_ADC2_ETRGREG_REMAP BIT(20)
#define AFIO_MAPR_ADC2_ETRGINJ_REMAP BIT(19)
#define AFIO_MAPR_ADC1_ETRGREG_REMAP BIT(18)
#define AFIO_MAPR_ADC1_ETRGINJ_REMAP BIT(17)
#define AFIO_MAPR_TIM5CH4_IREMAP BIT(16)
#define AFIO_MAPR_PD01_REMAP BIT(15)
#define AFIO_MAPR_CAN_REMAP (0x3 << 13)
#define AFIO_MAPR_CAN_REMAP_NONE (0x0 << 13)
#define AFIO_MAPR_CAN_REMAP_PB8_PB9 (0x2 << 13)
#define AFIO_MAPR_CAN_REMAP_PD0_PD1 (0x3 << 13)
#define AFIO_MAPR_TIM4_REMAP BIT(12)
#define AFIO_MAPR_TIM3_REMAP (0x3 << 10)
#define AFIO_MAPR_TIM3_REMAP_NONE (0x0 << 10)
#define AFIO_MAPR_TIM3_REMAP_PARTIAL (0x2 << 10)
#define AFIO_MAPR_TIM3_REMAP_FULL (0x3 << 10)
#define AFIO_MAPR_TIM2_REMAP (0x3 << 8)
#define AFIO_MAPR_TIM2_REMAP_NONE (0x0 << 8)
#define AFIO_MAPR_TIM2_REMAP_PA15_PB3_PA2_PA3 (0x1 << 8)
#define AFIO_MAPR_TIM2_REMAP_PA0_PA1_PB10_PB11 (0x2 << 8)
#define AFIO_MAPR_TIM2_REMAP_FULL (0x3 << 8)
#define AFIO_MAPR_TIM1_REMAP (0x3 << 6)
#define AFIO_MAPR_TIM1_REMAP_NONE (0x0 << 6)
#define AFIO_MAPR_TIM1_REMAP_PARTIAL (0x1 << 6)
#define AFIO_MAPR_TIM1_REMAP_FULL (0x3 << 6)
#define AFIO_MAPR_USART3_REMAP (0x3 << 4)
#define AFIO_MAPR_USART3_REMAP_NONE (0x0 << 4)
#define AFIO_MAPR_USART3_REMAP_PARTIAL (0x1 << 4)
#define AFIO_MAPR_USART3_REMAP_FULL (0x3 << 4)
#define AFIO_MAPR_USART2_REMAP BIT(3)
#define AFIO_MAPR_USART1_REMAP BIT(2)
#define AFIO_MAPR_I2C1_REMAP BIT(1)
#define AFIO_MAPR_SPI1_REMAP BIT(0)
/* External interrupt configuration register 1 */
#define AFIO_EXTICR1_EXTI3 (0xF << 12)
#define AFIO_EXTICR1_EXTI3_PA (0x0 << 12)
#define AFIO_EXTICR1_EXTI3_PB (0x1 << 12)
#define AFIO_EXTICR1_EXTI3_PC (0x2 << 12)
#define AFIO_EXTICR1_EXTI3_PD (0x3 << 12)
#define AFIO_EXTICR1_EXTI3_PE (0x4 << 12)
#define AFIO_EXTICR1_EXTI3_PF (0x5 << 12)
#define AFIO_EXTICR1_EXTI3_PG (0x6 << 12)
#define AFIO_EXTICR1_EXTI2 (0xF << 8)
#define AFIO_EXTICR1_EXTI2_PA (0x0 << 8)
#define AFIO_EXTICR1_EXTI2_PB (0x1 << 8)
#define AFIO_EXTICR1_EXTI2_PC (0x2 << 8)
#define AFIO_EXTICR1_EXTI2_PD (0x3 << 8)
#define AFIO_EXTICR1_EXTI2_PE (0x4 << 8)
#define AFIO_EXTICR1_EXTI2_PF (0x5 << 8)
#define AFIO_EXTICR1_EXTI2_PG (0x6 << 8)
#define AFIO_EXTICR1_EXTI1 (0xF << 4)
#define AFIO_EXTICR1_EXTI1_PA (0x0 << 4)
#define AFIO_EXTICR1_EXTI1_PB (0x1 << 4)
#define AFIO_EXTICR1_EXTI1_PC (0x2 << 4)
#define AFIO_EXTICR1_EXTI1_PD (0x3 << 4)
#define AFIO_EXTICR1_EXTI1_PE (0x4 << 4)
#define AFIO_EXTICR1_EXTI1_PF (0x5 << 4)
#define AFIO_EXTICR1_EXTI1_PG (0x6 << 4)
#define AFIO_EXTICR1_EXTI0 0xF
#define AFIO_EXTICR1_EXTI0_PA 0x0
#define AFIO_EXTICR1_EXTI0_PB 0x1
#define AFIO_EXTICR1_EXTI0_PC 0x2
#define AFIO_EXTICR1_EXTI0_PD 0x3
#define AFIO_EXTICR1_EXTI0_PE 0x4
#define AFIO_EXTICR1_EXTI0_PF 0x5
#define AFIO_EXTICR1_EXTI0_PG 0x6
/* External interrupt configuration register 2 */
#define AFIO_EXTICR2_EXTI7 (0xF << 12)
#define AFIO_EXTICR2_EXTI7_PA (0x0 << 12)
#define AFIO_EXTICR2_EXTI7_PB (0x1 << 12)
#define AFIO_EXTICR2_EXTI7_PC (0x2 << 12)
#define AFIO_EXTICR2_EXTI7_PD (0x3 << 12)
#define AFIO_EXTICR2_EXTI7_PE (0x4 << 12)
#define AFIO_EXTICR2_EXTI7_PF (0x5 << 12)
#define AFIO_EXTICR2_EXTI7_PG (0x6 << 12)
#define AFIO_EXTICR2_EXTI6 (0xF << 8)
#define AFIO_EXTICR2_EXTI6_PA (0x0 << 8)
#define AFIO_EXTICR2_EXTI6_PB (0x1 << 8)
#define AFIO_EXTICR2_EXTI6_PC (0x2 << 8)
#define AFIO_EXTICR2_EXTI6_PD (0x3 << 8)
#define AFIO_EXTICR2_EXTI6_PE (0x4 << 8)
#define AFIO_EXTICR2_EXTI6_PF (0x5 << 8)
#define AFIO_EXTICR2_EXTI6_PG (0x6 << 8)
#define AFIO_EXTICR2_EXTI5 (0xF << 4)
#define AFIO_EXTICR2_EXTI5_PA (0x0 << 4)
#define AFIO_EXTICR2_EXTI5_PB (0x1 << 4)
#define AFIO_EXTICR2_EXTI5_PC (0x2 << 4)
#define AFIO_EXTICR2_EXTI5_PD (0x3 << 4)
#define AFIO_EXTICR2_EXTI5_PE (0x4 << 4)
#define AFIO_EXTICR2_EXTI5_PF (0x5 << 4)
#define AFIO_EXTICR2_EXTI5_PG (0x6 << 4)
#define AFIO_EXTICR2_EXTI4 0xF
#define AFIO_EXTICR2_EXTI4_PA 0x0
#define AFIO_EXTICR2_EXTI4_PB 0x1
#define AFIO_EXTICR2_EXTI4_PC 0x2
#define AFIO_EXTICR2_EXTI4_PD 0x3
#define AFIO_EXTICR2_EXTI4_PE 0x4
#define AFIO_EXTICR2_EXTI4_PF 0x5
#define AFIO_EXTICR2_EXTI4_PG 0x6
/* AF remap and debug I/O configuration register 2 */
#define AFIO_MAPR2_FSMC_NADV BIT(10)
#define AFIO_MAPR2_TIM14_REMAP BIT(9)
#define AFIO_MAPR2_TIM13_REMAP BIT(8)
#define AFIO_MAPR2_TIM11_REMAP BIT(7)
#define AFIO_MAPR2_TIM10_REMAP BIT(6)
#define AFIO_MAPR2_TIM9_REMAP BIT(5)
/*
* AFIO convenience routines
*/
void afio_init(void);
/**
* External interrupt line numbers.
*/
typedef enum afio_exti_num {
AFIO_EXTI_0, /**< External interrupt line 0. */
AFIO_EXTI_1, /**< External interrupt line 1. */
AFIO_EXTI_2, /**< External interrupt line 2. */
AFIO_EXTI_3, /**< External interrupt line 3. */
AFIO_EXTI_4, /**< External interrupt line 4. */
AFIO_EXTI_5, /**< External interrupt line 5. */
AFIO_EXTI_6, /**< External interrupt line 6. */
AFIO_EXTI_7, /**< External interrupt line 7. */
AFIO_EXTI_8, /**< External interrupt line 8. */
AFIO_EXTI_9, /**< External interrupt line 9. */
AFIO_EXTI_10, /**< External interrupt line 10. */
AFIO_EXTI_11, /**< External interrupt line 11. */
AFIO_EXTI_12, /**< External interrupt line 12. */
AFIO_EXTI_13, /**< External interrupt line 13. */
AFIO_EXTI_14, /**< External interrupt line 14. */
AFIO_EXTI_15, /**< External interrupt line 15. */
} afio_exti_num;
void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port);
/* HACK: Use upper bit to denote MAPR2, Bit 31 is reserved and
* not used in either MAPR or MAPR2 */
#define AFIO_REMAP_USE_MAPR2 (1 << 31)
/**
* @brief Available peripheral remaps.
* @see afio_remap()
*/
typedef enum afio_remap_peripheral {
AFIO_REMAP_ADC2_ETRGREG = AFIO_MAPR_ADC2_ETRGREG_REMAP, /**<
ADC 2 external trigger regular conversion remapping */
AFIO_REMAP_ADC2_ETRGINJ = AFIO_MAPR_ADC2_ETRGINJ_REMAP, /**<
ADC 2 external trigger injected conversion remapping */
AFIO_REMAP_ADC1_ETRGREG = AFIO_MAPR_ADC1_ETRGREG_REMAP, /**<
ADC 1 external trigger regular conversion remapping */
AFIO_REMAP_ADC1_ETRGINJ = AFIO_MAPR_ADC1_ETRGINJ_REMAP, /**<
ADC 1 external trigger injected conversion remapping */
AFIO_REMAP_TIM5CH4_I = AFIO_MAPR_TIM5CH4_IREMAP, /**<
Timer 5 channel 4 internal remapping */
AFIO_REMAP_PD01 = AFIO_MAPR_PD01_REMAP, /**<
Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
AFIO_REMAP_CAN_1 = AFIO_MAPR_CAN_REMAP_PB8_PB9, /**<
CAN alternate function remapping 1 (RX on PB8, TX on PB9) */
AFIO_REMAP_CAN_2 = AFIO_MAPR_CAN_REMAP_PD0_PD1, /**<
CAN alternate function remapping 2 (RX on PD0, TX on PD1) */
AFIO_REMAP_TIM4 = AFIO_MAPR_TIM4_REMAP, /**<
Timer 4 remapping */
AFIO_REMAP_TIM3_PARTIAL = AFIO_MAPR_TIM3_REMAP_PARTIAL, /**<
Timer 3 partial remapping */
AFIO_REMAP_TIM3_FULL = AFIO_MAPR_TIM3_REMAP_FULL, /**<
Timer 3 full remapping */
AFIO_REMAP_TIM2_PARTIAL_1 = AFIO_MAPR_TIM2_REMAP_PA15_PB3_PA2_PA3, /**<
Timer 2 partial remapping 1 (CH1 and ETR on PA15, CH2 on PB3, CH3
on PA2, CH4 on PA3) */
AFIO_REMAP_TIM2_PARTIAL_2 = AFIO_MAPR_TIM2_REMAP_PA0_PA1_PB10_PB11, /**<
Timer 2 partial remapping 2 (CH1 and ETR on PA0, CH2 on PA1, CH3
on PB10, CH4 on PB11) */
AFIO_REMAP_TIM2_FULL = AFIO_MAPR_TIM2_REMAP_FULL, /**<
Timer 2 full remapping */
AFIO_REMAP_USART2 = AFIO_MAPR_USART2_REMAP, /**<
USART 2 remapping */
AFIO_REMAP_USART1 = AFIO_MAPR_USART1_REMAP, /**<
USART 1 remapping */
AFIO_REMAP_I2C1 = AFIO_MAPR_I2C1_REMAP, /**<
I2C 1 remapping */
AFIO_REMAP_SPI1 = AFIO_MAPR_SPI1_REMAP, /**<
SPI 1 remapping */
AFIO_REMAP_FSMC_NADV = (AFIO_MAPR2_FSMC_NADV |
AFIO_REMAP_USE_MAPR2), /**<
NADV signal not connected */
AFIO_REMAP_TIM14 = (AFIO_MAPR2_TIM14_REMAP |
AFIO_REMAP_USE_MAPR2), /**<
Timer 14 remapping */
AFIO_REMAP_TIM13 = (AFIO_MAPR2_TIM13_REMAP |
AFIO_REMAP_USE_MAPR2), /**<
Timer 13 remapping */
AFIO_REMAP_TIM11 = (AFIO_MAPR2_TIM11_REMAP |
AFIO_REMAP_USE_MAPR2), /**<
Timer 11 remapping */
AFIO_REMAP_TIM10 = (AFIO_MAPR2_TIM10_REMAP |
AFIO_REMAP_USE_MAPR2), /**<
Timer 10 remapping */
AFIO_REMAP_TIM9 = (AFIO_MAPR2_TIM9_REMAP |
AFIO_REMAP_USE_MAPR2) /**<
Timer 9 */
} afio_remap_peripheral;
void afio_remap(afio_remap_peripheral p);
/**
* @brief Debug port configuration
*
* Used to configure the behavior of JTAG and Serial Wire (SW) debug
* ports and their associated GPIO pins.
*
* @see afio_cfg_debug_ports()
*/
typedef enum afio_debug_cfg {
AFIO_DEBUG_FULL_SWJ = AFIO_MAPR_SWJ_CFG_FULL_SWJ, /**<
Full Serial Wire and JTAG debug */
AFIO_DEBUG_FULL_SWJ_NO_NJRST = AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST, /**<
Full Serial Wire and JTAG, but no NJTRST. */
AFIO_DEBUG_SW_ONLY = AFIO_MAPR_SWJ_CFG_NO_JTAG_SW, /**<
Serial Wire debug only (JTAG-DP disabled,
SW-DP enabled) */
AFIO_DEBUG_NONE = AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW /**<
No debug; all JTAG and SW pins are free
for use as GPIOs. */
} afio_debug_cfg;
/**
* @brief Enable or disable the JTAG and SW debug ports.
* @param config Desired debug port configuration
* @see afio_debug_cfg
*/
static inline void afio_cfg_debug_ports(afio_debug_cfg config) {
//__io uint32 *mapr = &AFIO_BASE->MAPR;
//*mapr = (*mapr & ~AFIO_MAPR_SWJ_CFG) | config;
}
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,707 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#ifdef STM32F4
/**
* @file rcc.c
* @brief Implements pretty much only the basic clock setup on the
* stm32, clock enable/disable and peripheral reset commands.
*/
#include "libmaple.h"
#include "flash.h"
#include "gpio.h"
#include "rcc.h"
#include "bitband.h"
#define APB1 RCC_APB1
#define APB2 RCC_APB2
#define AHB1 RCC_AHB1
#define AHB2 RCC_AHB2
#define AHB3 RCC_AHB3
struct rcc_dev_info {
const rcc_clk_domain clk_domain;
const uint8 line_num;
};
static uint32 rcc_dev_clk_speed_table[AHB3];
/* Device descriptor table, maps rcc_clk_id onto bus and enable/reset
* register bit numbers. */
static const struct rcc_dev_info rcc_dev_table[] = {
[RCC_GPIOA] = { .clk_domain = AHB1, .line_num = 0 }, //*
[RCC_GPIOB] = { .clk_domain = AHB1, .line_num = 1 }, //*
[RCC_GPIOC] = { .clk_domain = AHB1, .line_num = 2 }, //*
[RCC_GPIOD] = { .clk_domain = AHB1, .line_num = 3 }, //*
// [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 },
[RCC_ADC1] = { .clk_domain = APB2, .line_num = 8 }, //*
[RCC_ADC2] = { .clk_domain = APB2, .line_num = 9 }, //*
[RCC_ADC3] = { .clk_domain = APB2, .line_num = 10 }, //*
[RCC_USART1] = { .clk_domain = APB2, .line_num = 4 }, //*
[RCC_USART2] = { .clk_domain = APB1, .line_num = 17 }, //unchanged
[RCC_USART3] = { .clk_domain = APB1, .line_num = 18 }, //unchanged
[RCC_TIMER1] = { .clk_domain = APB2, .line_num = 0 }, //*
[RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 }, //unchanged
[RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 }, //unchanged
[RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 }, //unchanged
[RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 }, //unchanged
[RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 }, //unchanged
[RCC_DMA1] = { .clk_domain = AHB1, .line_num = 21 }, //*
[RCC_PWR] = { .clk_domain = APB1, .line_num = 28}, //unchanged
[RCC_BKP] = { .clk_domain = AHB1, .line_num = 18}, //*
[RCC_I2C1] = { .clk_domain = APB1, .line_num = 21 }, //unchanged
[RCC_I2C2] = { .clk_domain = APB1, .line_num = 22 }, //unchanged
[RCC_CRC] = { .clk_domain = AHB1, .line_num = 12}, //*
// [RCC_FLITF] = { .clk_domain = AHB, .line_num = 4},
// [RCC_SRAM] = { .clk_domain = AHB, .line_num = 2},
[RCC_GPIOE] = { .clk_domain = AHB1, .line_num = 4 }, //*
[RCC_GPIOF] = { .clk_domain = AHB1, .line_num = 5 }, //*
[RCC_GPIOG] = { .clk_domain = AHB1, .line_num = 6 }, //*
[RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, //unchanged
[RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, //unchanged
[RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, //unchanged
[RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, //unchanged
[RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, //unchanged
[RCC_TIMER8] = { .clk_domain = APB2, .line_num = 1 }, //*
[RCC_FSMC] = { .clk_domain = AHB3, .line_num = 0 }, //*
[RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, //unchanged
[RCC_DMA2] = { .clk_domain = AHB1, .line_num = 22 }, //*
[RCC_SDIO] = { .clk_domain = APB2, .line_num = 11 }, //*
[RCC_SPI3] = { .clk_domain = APB1, .line_num = 15 }, //unchanged
[RCC_TIMER9] = { .clk_domain = APB2, .line_num = 16 }, //*
[RCC_TIMER10] = { .clk_domain = APB2, .line_num = 17 }, //*
[RCC_TIMER11] = { .clk_domain = APB2, .line_num = 18 }, //*
[RCC_TIMER12] = { .clk_domain = APB1, .line_num = 6 }, //unchanged
[RCC_TIMER13] = { .clk_domain = APB1, .line_num = 7 }, //unchanged
[RCC_TIMER14] = { .clk_domain = APB1, .line_num = 8 }, //unchanged
[RCC_USBFS] = { .clk_domain = AHB2, .line_num = 7 }, //*
[RCC_SYSCFG] = { .clk_domain = APB2, .line_num = 14 }, //*
[RCC_SPI4] = { .clk_domain = APB1, .line_num = 15 },
};
/**
* @brief Initialize the clock control system. Initializes the system
* clock source to use the PLL driven by an external oscillator
* @param sysclk_src system clock source, must be PLL
* @param pll_src pll clock source, must be HSE
* @param pll_mul pll multiplier
*/
#define HSE_STARTUP_TIMEOUT ((uint16)0x0500) /*!< Time out for HSE start up */
#define RCC_CFGR_HPRE_DIV1 ((uint32)0x00000000) /*!< SYSCLK not divided */
#define RCC_CFGR_PPRE1_DIV2 ((uint32)0x00001000) /*!< HCLK divided by 2 */
#define RCC_CFGR_PPRE1_DIV4 ((uint32)0x00001400) /*!< HCLK divided by 4 */
#define RCC_CFGR_PPRE2_DIV1 ((uint32)0x00000000) /*!< HCLK not divided */
#define RCC_CFGR_PPRE2_DIV2 ((uint32)0x00008000) /*!< HCLK divided by 2 */
#define RCC_PLLCFGR_PLLSRC_HSE ((uint32)0x00400000)
/******************* Bits definition for FLASH_ACR register *****************/
//#define FLASH_ACR_LATENCY ((uint32_t)0x00000007)
#define FLASH_ACR_LATENCY_0WS ((uint32)0x00000000)
#define FLASH_ACR_LATENCY_1WS ((uint32)0x00000001)
#define FLASH_ACR_LATENCY_2WS ((uint32)0x00000002)
#define FLASH_ACR_LATENCY_3WS ((uint32)0x00000003)
#define FLASH_ACR_LATENCY_4WS ((uint32)0x00000004)
#define FLASH_ACR_LATENCY_5WS ((uint32)0x00000005)
#define FLASH_ACR_LATENCY_6WS ((uint32)0x00000006)
#define FLASH_ACR_LATENCY_7WS ((uint32)0x00000007)
#define FLASH_ACR_PRFTEN ((uint32)0x00000100)
#define FLASH_ACR_ICEN ((uint32)0x00000200)
#define FLASH_ACR_DCEN ((uint32)0x00000400)
#define FLASH_ACR_ICRST ((uint32)0x00000800)
#define FLASH_ACR_DCRST ((uint32)0x00001000)
#define FLASH_ACR_BYTE0_ADDRESS ((uint32)0x40023C00)
#define FLASH_ACR_BYTE2_ADDRESS ((uint32)0x40023C03)
typedef struct
{
__io uint32 CR; /*!< PWR power control register, Address offset: 0x00 */
__io uint32 CSR; /*!< PWR power control/status register, Address offset: 0x04 */
} PWR_TypeDef;
#define PWR_BASE (0x40007000)
#define PWR ((PWR_TypeDef *) PWR_BASE)
#define PWR_CR_VOS ((uint16)0x4000) /*!< Regulator voltage scaling output selection */
typedef struct
{
__io uint32 ACR; /*!< FLASH access control register, Address offset: 0x00 */
__io uint32 KEYR; /*!< FLASH key register, Address offset: 0x04 */
__io uint32 OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */
__io uint32 SR; /*!< FLASH status register, Address offset: 0x0C */
__io uint32 CR; /*!< FLASH control register, Address offset: 0x10 */
__io uint32 OPTCR; /*!< FLASH option control register, Address offset: 0x14 */
} FLASH_TypeDef;
#define FLASH_R_BASE (0x40023C00)
#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE)
#define RESET 0
typedef uint32 uint32_t;
void InitMCO1()
{
rcc_reg_map *RCC = RCC_BASE;
// Turn MCO1 Master Clock Output mode
RCC->CFGR &= RCC_CFGR_MCO1_RESET_MASK;
RCC->CFGR |= RCC_CFGR_MCO1Source_HSE | RCC_CFGR_MCO1Div_1;
// PA8 Output the Master Clock MCO1
gpio_set_af_mode(GPIOA, 8, 0);
gpio_set_mode(GPIOA, 8, GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
}
void SetupClock72MHz()
{
uint32_t SystemCoreClock = 72000000;
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
/************************* PLL Parameters *************************************/
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
int PLL_M = 4;
int PLL_N = 216;
/* SYSCLK = PLL_VCO / PLL_P */
int PLL_P = 6;
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
int PLL_Q = 9;
uint32 StartUpCounter = 0, HSEStatus = 0;
rcc_reg_map *RCC = RCC_BASE;
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Select regulator voltage output Scale 2 mode, System frequency up to 144 MHz */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR &= (uint32_t)~(PWR_CR_VOS);
/* HCLK = SYSCLK / 1*/
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 1*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
// save bus clock values
rcc_dev_clk_speed_table[RCC_AHB1] = (SystemCoreClock/1);
rcc_dev_clk_speed_table[RCC_APB2] = (SystemCoreClock/1);
rcc_dev_clk_speed_table[RCC_APB1] = (SystemCoreClock/2);
/* Configure the main PLL */
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
/* Enable the main PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till the main PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
/* Select the main PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= RCC_CFGR_SW_PLL;
/* Wait till the main PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
void SetupClock120MHz()
{
uint32_t SystemCoreClock = 120000000;
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
/************************* PLL Parameters *************************************/
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
int PLL_M = 8;
int PLL_N = 240;
/* SYSCLK = PLL_VCO / PLL_P */
int PLL_P = 2;
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
int PLL_Q = 5;
uint32 StartUpCounter = 0, HSEStatus = 0;
rcc_reg_map *RCC = RCC_BASE;
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Select regulator voltage output Scale 2 mode, System frequency up to 144 MHz */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR &= (uint32_t)~(PWR_CR_VOS);
/* HCLK = SYSCLK / 1*/
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
// save bus clock values
rcc_dev_clk_speed_table[RCC_AHB1] = (SystemCoreClock/1);
rcc_dev_clk_speed_table[RCC_APB2] = (SystemCoreClock/2);
rcc_dev_clk_speed_table[RCC_APB1] = (SystemCoreClock/4);
/* Configure the main PLL */
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
/* Enable the main PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till the main PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_3WS;
/* Select the main PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= RCC_CFGR_SW_PLL;
/* Wait till the main PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
void SetupClock168MHz()
{
uint32_t SystemCoreClock = 168000000;
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
/************************* PLL Parameters *************************************/
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
#ifdef ARDUINO_STM32F4_NETDUINO2PLUS
int PLL_M = 25; // The NETDUINO has a 25MHz external oscillator
#else
int PLL_M = 8;
#endif
int PLL_N = 336;
/* SYSCLK = PLL_VCO / PLL_P */
int PLL_P = 2;
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
int PLL_Q = 7;
uint32 StartUpCounter = 0, HSEStatus = 0;
rcc_reg_map *RCC = RCC_BASE;
#ifdef ARDUINO_STM32F4_NETDUINO2PLUS
InitMCO1();
#endif
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_VOS;
/* HCLK = SYSCLK / 1*/
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
// save bus clock values
rcc_dev_clk_speed_table[RCC_AHB1] = (SystemCoreClock/1);
rcc_dev_clk_speed_table[RCC_APB2] = (SystemCoreClock/2);
rcc_dev_clk_speed_table[RCC_APB1] = (SystemCoreClock/4);
/* Configure the main PLL */
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
/* Enable the main PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till the main PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
/* Select the main PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= RCC_CFGR_SW_PLL;
/* Wait till the main PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
void rcc_clk_init(rcc_sysclk_src sysclk_src,
rcc_pllsrc pll_src,
rcc_pll_multiplier pll_mul) {
//SetupClock72MHz();
#if STM32_TICKS_PER_US == 168
SetupClock168MHz();
#endif
#if STM32_TICKS_PER_US == 120
SetupClock120MHz();
#endif
#if STM32_TICKS_PER_US == 72
SetupClock72MHz();
#endif
}
#define PLL_M 8
#define PLL_N 240
/* SYSCLK = PLL_VCO / PLL_P */
#define PLL_P 2
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
#define PLL_Q 5
void rcc_clk_init2(rcc_sysclk_src sysclk_src,
rcc_pllsrc pll_src,
rcc_pll_multiplier pll_mul) {
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
uint32 StartUpCounter = 0, HSEStatus = 0;
rcc_reg_map *pRCC = RCC_BASE;
/* Enable HSE */
pRCC->CR |= RCC_CR_HSEON;
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = pRCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((pRCC->CR & RCC_CR_HSERDY) != 0)
{
HSEStatus = 0x01;
}
else
{
HSEStatus = 0x00;
}
if (HSEStatus == 0x01)
{
/* HCLK = SYSCLK / 1*/
pRCC->CFGR |= RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 2*/
pRCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/
pRCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
/* Configure the main PLL */
pRCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
/* Enable the main PLL */
pRCC->CR |= RCC_CR_PLLON;
/* Wait till the main PLL is ready */
while((pRCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
((FLASH_TypeDef*)FLASH)->ACR = FLASH_ACR_PRFTEN |FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_3WS;
/* Select the main PLL as system clock source */
pRCC->CFGR &= ~RCC_CFGR_SW;
pRCC->CFGR |= RCC_CFGR_SW_PLL;
/* Wait till the main PLL is used as system clock source */
while ((pRCC->CFGR & RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
#if 0
uint32 cfgr = 0;
uint32 cr;
/* Assume that we're going to clock the chip off the PLL, fed by
* the HSE */
ASSERT(sysclk_src == RCC_CLKSRC_PLL &&
pll_src == RCC_PLLSRC_HSE);
RCC_BASE->CFGR = pll_src | pll_mul;
/* Turn on the HSE */
cr = RCC_BASE->CR;
cr |= RCC_CR_HSEON;
RCC_BASE->CR = cr;
while (!(RCC_BASE->CR & RCC_CR_HSERDY))
;
/* Now the PLL */
cr |= RCC_CR_PLLON;
RCC_BASE->CR = cr;
while (!(RCC_BASE->CR & RCC_CR_PLLRDY))
;
/* Finally, let's switch over to the PLL */
cfgr &= ~RCC_CFGR_SW;
cfgr |= RCC_CFGR_SW_PLL;
RCC_BASE->CFGR = cfgr;
while ((RCC_BASE->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL)
;
#endif
}
/**
* @brief Turn on the clock line on a peripheral
* @param id Clock ID of the peripheral to turn on.
*/
void rcc_clk_enable(rcc_clk_id id) {
static const __io uint32* enable_regs[] = {
[APB1] = &RCC_BASE->APB1ENR,
[APB2] = &RCC_BASE->APB2ENR,
[AHB1] = &RCC_BASE->AHB1ENR,
[AHB2] = &RCC_BASE->AHB2ENR,
[AHB3] = &RCC_BASE->AHB3ENR,
};
rcc_clk_domain clk_domain = rcc_dev_clk(id);
__io uint32* enr = (__io uint32*)enable_regs[clk_domain];
uint8 lnum = rcc_dev_table[id].line_num;
bb_peri_set_bit(enr, lnum, 1);
}
/**
* @brief Turn on the clock line on a peripheral
* @param id Clock ID of the peripheral to turn on.
*/
void rcc_clk_disable(rcc_clk_id id) {
static const __io uint32* enable_regs[] = {
[APB1] = &RCC_BASE->APB1ENR,
[APB2] = &RCC_BASE->APB2ENR,
[AHB1] = &RCC_BASE->AHB1ENR,
[AHB2] = &RCC_BASE->AHB2ENR,
[AHB3] = &RCC_BASE->AHB3ENR,
};
rcc_clk_domain clk_domain = rcc_dev_clk(id);
__io uint32* enr = (__io uint32*)enable_regs[clk_domain];
uint8 lnum = rcc_dev_table[id].line_num;
bb_peri_set_bit(enr, lnum, 0);
}
/**
* @brief Reset a peripheral.
* @param id Clock ID of the peripheral to reset.
*/
void rcc_reset_dev(rcc_clk_id id) {
static const __io uint32* reset_regs[] = {
[APB1] = &RCC_BASE->APB1RSTR,
[APB2] = &RCC_BASE->APB2RSTR,
[AHB1] = &RCC_BASE->AHB1RSTR,
[AHB2] = &RCC_BASE->AHB2RSTR,
[AHB3] = &RCC_BASE->AHB3RSTR,
};
rcc_clk_domain clk_domain = rcc_dev_clk(id);
__io void* addr = (__io void*)reset_regs[clk_domain];
uint8 lnum = rcc_dev_table[id].line_num;
bb_peri_set_bit(addr, lnum, 1);
bb_peri_set_bit(addr, lnum, 0);
}
/**
* @brief Get a peripheral's clock domain
* @param id Clock ID of the peripheral whose clock domain to return
* @return Clock source for the given clock ID
*/
rcc_clk_domain rcc_dev_clk(rcc_clk_id id) {
return rcc_dev_table[id].clk_domain;
}
/**
* @brief Get a peripheral's clock domain speed
* @param id Clock ID of the peripheral whose clock domain speed to return
* @return Clock speed for the given clock ID
*/
uint32 rcc_dev_clk_speed(rcc_clk_id id) {
return rcc_dev_clk_speed_table[rcc_dev_clk(id)];
}
/**
* @brief Get a peripheral's timer clock domain speed
* @param id Clock ID of the peripheral whose clock domain speed to return
* @return Clock speed for the given clock ID
*/
uint32 rcc_dev_timer_clk_speed(rcc_clk_id id) {
return 2*rcc_dev_clk_speed(id);
}
/**
* @brief Set the divider on a peripheral prescaler
* @param prescaler prescaler to set
* @param divider prescaler divider
*/
void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) {
#if 0
static const uint32 masks[] = {
[RCC_PRESCALER_AHB] = RCC_CFGR_HPRE,
[RCC_PRESCALER_APB1] = RCC_CFGR_PPRE1,
[RCC_PRESCALER_APB2] = RCC_CFGR_PPRE2,
[RCC_PRESCALER_USB] = RCC_CFGR_USBPRE,
[RCC_PRESCALER_ADC] = RCC_CFGR_ADCPRE,
};
uint32 cfgr = RCC_BASE->CFGR;
cfgr &= ~masks[prescaler];
cfgr |= divider;
RCC_BASE->CFGR = cfgr;
#endif
}
#endif

View File

@ -0,0 +1,642 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file rcc.h
* @brief reset and clock control definitions and prototypes
*/
#include "libmaple_types.h"
#include "bitband.h"
#ifndef _RCC_H_
#define _RCC_H_
#ifdef __cplusplus
extern "C"{
#endif
/** RCC register map type */
typedef struct
{
__io uint32 CR; /*!< RCC clock control register, Address offset: 0x00 */
__io uint32 PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */
__io uint32 CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */
__io uint32 CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */
__io uint32 AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */
__io uint32 AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */
__io uint32 AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */
uint32 RESERVED0; /*!< Reserved, 0x1C */
__io uint32 APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */
__io uint32 APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */
uint32 RESERVED1[2]; /*!< Reserved, 0x28-0x2C */
__io uint32 AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */
__io uint32 AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */
__io uint32 AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */
uint32 RESERVED2; /*!< Reserved, 0x3C */
__io uint32 APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */
__io uint32 APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */
uint32 RESERVED3[2]; /*!< Reserved, 0x48-0x4C */
__io uint32 AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */
__io uint32 AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */
__io uint32 AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */
uint32 RESERVED4; /*!< Reserved, 0x5C */
__io uint32 APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */
__io uint32 APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */
uint32 RESERVED5[2]; /*!< Reserved, 0x68-0x6C */
__io uint32 BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */
__io uint32 CSR; /*!< RCC clock control & status register, Address offset: 0x74 */
uint32 RESERVED6[2]; /*!< Reserved, 0x78-0x7C */
__io uint32 SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */
__io uint32 PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */
} rcc_reg_map;
/** RCC register map base pointer */
//#define RCC_BASE ((struct rcc_reg_map*)0x40021000)
#define RCC_BASE ((rcc_reg_map*)0x40023800)
/*
* Register bit definitions
*/
/* Clock control register */
#define RCC_CR_PLLRDY_BIT 25
#define RCC_CR_PLLON_BIT 24
#define RCC_CR_CSSON_BIT 19
#define RCC_CR_HSEBYP_BIT 18
#define RCC_CR_HSERDY_BIT 17
#define RCC_CR_HSEON_BIT 16
#define RCC_CR_HSIRDY_BIT 1
#define RCC_CR_HSION_BIT 0
#define RCC_CR_PLLRDY BIT(RCC_CR_PLLRDY_BIT)
#define RCC_CR_PLLON BIT(RCC_CR_PLLON_BIT)
#define RCC_CR_CSSON BIT(RCC_CR_CSSON_BIT)
#define RCC_CR_HSEBYP BIT(RCC_CR_HSEBYP_BIT)
#define RCC_CR_HSERDY BIT(RCC_CR_HSERDY_BIT)
#define RCC_CR_HSEON BIT(RCC_CR_HSEON_BIT)
#define RCC_CR_HSICAL (0xFF << 8)
#define RCC_CR_HSITRIM (0x1F << 3)
#define RCC_CR_HSIRDY BIT(RCC_CR_HSIRDY_BIT)
#define RCC_CR_HSION BIT(RCC_CR_HSION_BIT)
/* Clock configuration register */
#define RCC_CFGR_USBPRE_BIT 22
#define RCC_CFGR_PLLXTPRE_BIT 17
#define RCC_CFGR_PLLSRC_BIT 16
#define RCC_CFGR_MCO (0x3 << 24)
#define RCC_CFGR_USBPRE BIT(RCC_CFGR_USBPRE_BIT)
#define RCC_CFGR_PLLMUL (0xF << 18)
#define RCC_CFGR_PLLXTPRE BIT(RCC_CFGR_PLLXTPRE_BIT)
#define RCC_CFGR_PLLSRC BIT(RCC_CFGR_PLLSRC_BIT)
#define RCC_CFGR_ADCPRE (0x3 << 14)
#define RCC_CFGR_PPRE2 (0x7 << 11)
#define RCC_CFGR_PPRE1 (0x7 << 8)
#define RCC_CFGR_HPRE (0xF << 4)
#define RCC_CFGR_SWS (0x3 << 2)
#define RCC_CFGR_SWS_PLL (0x2 << 2)
#define RCC_CFGR_SWS_HSE (0x1 << 2)
#define RCC_CFGR_SW 0x3
#define RCC_CFGR_SW_PLL 0x2
#define RCC_CFGR_SW_HSE 0x1
#define RCC_CFGR_MCO1Source_HSI ((uint32_t)0x00000000)
#define RCC_CFGR_MCO1Source_LSE ((uint32_t)0x00200000)
#define RCC_CFGR_MCO1Source_HSE ((uint32_t)0x00400000)
#define RCC_CFGR_MCO1Source_PLLCLK ((uint32_t)0x00600000)
#define RCC_CFGR_MCO1Div_1 ((uint32_t)0x00000000)
#define RCC_CFGR_MCO1Div_2 ((uint32_t)0x04000000)
#define RCC_CFGR_MCO1Div_3 ((uint32_t)0x05000000)
#define RCC_CFGR_MCO1Div_4 ((uint32_t)0x06000000)
#define RCC_CFGR_MCO1Div_5 ((uint32_t)0x07000000)
#define RCC_CFGR_MCO1_RESET_MASK ((uint32_t)0xF89FFFFF)
/* Clock interrupt register */
#define RCC_CIR_CSSC_BIT 23
#define RCC_CIR_PLLRDYC_BIT 20
#define RCC_CIR_HSERDYC_BIT 19
#define RCC_CIR_HSIRDYC_BIT 18
#define RCC_CIR_LSERDYC_BIT 17
#define RCC_CIR_LSIRDYC_BIT 16
#define RCC_CIR_PLLRDYIE_BIT 12
#define RCC_CIR_HSERDYIE_BIT 11
#define RCC_CIR_HSIRDYIE_BIT 10
#define RCC_CIR_LSERDYIE_BIT 9
#define RCC_CIR_LSIRDYIE_BIT 8
#define RCC_CIR_CSSF_BIT 7
#define RCC_CIR_PLLRDYF_BIT 4
#define RCC_CIR_HSERDYF_BIT 3
#define RCC_CIR_HSIRDYF_BIT 2
#define RCC_CIR_LSERDYF_BIT 1
#define RCC_CIR_LSIRDYF_BIT 0
#define RCC_CIR_CSSC BIT(RCC_CIR_CSSC_BIT)
#define RCC_CIR_PLLRDYC BIT(RCC_CIR_PLLRDYC_BIT)
#define RCC_CIR_HSERDYC BIT(RCC_CIR_HSERDYC_BIT)
#define RCC_CIR_HSIRDYC BIT(RCC_CIR_HSIRDYC_BIT)
#define RCC_CIR_LSERDYC BIT(RCC_CIR_LSERDYC_BIT)
#define RCC_CIR_LSIRDYC BIT(RCC_CIR_LSIRDYC_BIT)
#define RCC_CIR_PLLRDYIE BIT(RCC_CIR_PLLRDYIE_BIT)
#define RCC_CIR_HSERDYIE BIT(RCC_CIR_HSERDYIE_BIT)
#define RCC_CIR_HSIRDYIE BIT(RCC_CIR_HSIRDYIE_BIT)
#define RCC_CIR_LSERDYIE BIT(RCC_CIR_LSERDYIE_BIT)
#define RCC_CIR_LSIRDYIE BIT(RCC_CIR_LSIRDYIE_BIT)
#define RCC_CIR_CSSF BIT(RCC_CIR_CSSF_BIT)
#define RCC_CIR_PLLRDYF BIT(RCC_CIR_PLLRDYF_BIT)
#define RCC_CIR_HSERDYF BIT(RCC_CIR_HSERDYF_BIT)
#define RCC_CIR_HSIRDYF BIT(RCC_CIR_HSIRDYF_BIT)
#define RCC_CIR_LSERDYF BIT(RCC_CIR_LSERDYF_BIT)
#define RCC_CIR_LSIRDYF BIT(RCC_CIR_LSIRDYF_BIT)
/* APB2 peripheral reset register */
#define RCC_APB2RSTR_TIM11RST_BIT 21
#define RCC_APB2RSTR_TIM10RST_BIT 20
#define RCC_APB2RSTR_TIM9RST_BIT 19
#define RCC_APB2RSTR_ADC3RST_BIT 15
#define RCC_APB2RSTR_USART1RST_BIT 14
#define RCC_APB2RSTR_TIM8RST_BIT 13
#define RCC_APB2RSTR_SPI1RST_BIT 12
#define RCC_APB2RSTR_TIM1RST_BIT 11
#define RCC_APB2RSTR_ADC2RST_BIT 10
#define RCC_APB2RSTR_ADC1RST_BIT 9
#define RCC_APB2RSTR_IOPGRST_BIT 8
#define RCC_APB2RSTR_IOPFRST_BIT 7
#define RCC_APB2RSTR_IOPERST_BIT 6
#define RCC_APB2RSTR_IOPDRST_BIT 5
#define RCC_APB2RSTR_IOPCRST_BIT 4
#define RCC_APB2RSTR_IOPBRST_BIT 3
#define RCC_APB2RSTR_IOPARST_BIT 2
#define RCC_APB2RSTR_AFIORST_BIT 0
#define RCC_APB2RSTR_TIM11RST BIT(RCC_APB2RSTR_TIM11RST_BIT)
#define RCC_APB2RSTR_TIM10RST BIT(RCC_APB2RSTR_TIM10RST_BIT)
#define RCC_APB2RSTR_TIM9RST BIT(RCC_APB2RSTR_TIM9RST_BIT)
#define RCC_APB2RSTR_ADC3RST BIT(RCC_APB2RSTR_ADC3RST_BIT)
#define RCC_APB2RSTR_USART1RST BIT(RCC_APB2RSTR_USART1RST_BIT)
#define RCC_APB2RSTR_TIM8RST BIT(RCC_APB2RSTR_TIM8RST_BIT)
#define RCC_APB2RSTR_SPI1RST BIT(RCC_APB2RSTR_SPI1RST_BIT)
#define RCC_APB2RSTR_TIM1RST BIT(RCC_APB2RSTR_TIM1RST_BIT)
#define RCC_APB2RSTR_ADC2RST BIT(RCC_APB2RSTR_ADC2RST_BIT)
#define RCC_APB2RSTR_ADC1RST BIT(RCC_APB2RSTR_ADC1RST_BIT)
#define RCC_APB2RSTR_IOPGRST BIT(RCC_APB2RSTR_IOPGRST_BIT)
#define RCC_APB2RSTR_IOPFRST BIT(RCC_APB2RSTR_IOPFRST_BIT)
#define RCC_APB2RSTR_IOPERST BIT(RCC_APB2RSTR_IOPERST_BIT)
#define RCC_APB2RSTR_IOPDRST BIT(RCC_APB2RSTR_IOPDRST_BIT)
#define RCC_APB2RSTR_IOPCRST BIT(RCC_APB2RSTR_IOPCRST_BIT)
#define RCC_APB2RSTR_IOPBRST BIT(RCC_APB2RSTR_IOPBRST_BIT)
#define RCC_APB2RSTR_IOPARST BIT(RCC_APB2RSTR_IOPARST_BIT)
#define RCC_APB2RSTR_AFIORST BIT(RCC_APB2RSTR_AFIORST_BIT)
/* APB1 peripheral reset register */
#define RCC_APB1RSTR_DACRST_BIT 29
#define RCC_APB1RSTR_PWRRST_BIT 28
#define RCC_APB1RSTR_BKPRST_BIT 27
#define RCC_APB1RSTR_CANRST_BIT 25
#define RCC_APB1RSTR_USBRST_BIT 23
#define RCC_APB1RSTR_I2C2RST_BIT 22
#define RCC_APB1RSTR_I2C1RST_BIT 21
#define RCC_APB1RSTR_UART5RST_BIT 20
#define RCC_APB1RSTR_UART4RST_BIT 19
#define RCC_APB1RSTR_USART3RST_BIT 18
#define RCC_APB1RSTR_USART2RST_BIT 17
#define RCC_APB1RSTR_SPI3RST_BIT 15
#define RCC_APB1RSTR_SPI2RST_BIT 14
#define RCC_APB1RSTR_WWDRST_BIT 11
#define RCC_APB1RSTR_TIM14RST_BIT 8
#define RCC_APB1RSTR_TIM13RST_BIT 7
#define RCC_APB1RSTR_TIM12RST_BIT 6
#define RCC_APB1RSTR_TIM7RST_BIT 5
#define RCC_APB1RSTR_TIM6RST_BIT 4
#define RCC_APB1RSTR_TIM5RST_BIT 3
#define RCC_APB1RSTR_TIM4RST_BIT 2
#define RCC_APB1RSTR_TIM3RST_BIT 1
#define RCC_APB1RSTR_TIM2RST_BIT 0
#define RCC_APB1RSTR_DACRST BIT(RCC_APB1RSTR_DACRST_BIT)
#define RCC_APB1RSTR_PWRRST BIT(RCC_APB1RSTR_PWRRST_BIT)
#define RCC_APB1RSTR_BKPRST BIT(RCC_APB1RSTR_BKPRST_BIT)
#define RCC_APB1RSTR_CANRST BIT(RCC_APB1RSTR_CANRST_BIT)
#define RCC_APB1RSTR_USBRST BIT(RCC_APB1RSTR_USBRST_BIT)
#define RCC_APB1RSTR_I2C2RST BIT(RCC_APB1RSTR_I2C2RST_BIT)
#define RCC_APB1RSTR_I2C1RST BIT(RCC_APB1RSTR_I2C1RST_BIT)
#define RCC_APB1RSTR_UART5RST BIT(RCC_APB1RSTR_UART5RST_BIT)
#define RCC_APB1RSTR_UART4RST BIT(RCC_APB1RSTR_UART4RST_BIT)
#define RCC_APB1RSTR_USART3RST BIT(RCC_APB1RSTR_USART3RST_BIT)
#define RCC_APB1RSTR_USART2RST BIT(RCC_APB1RSTR_USART2RST_BIT)
#define RCC_APB1RSTR_SPI3RST BIT(RCC_APB1RSTR_SPI3RST_BIT)
#define RCC_APB1RSTR_SPI2RST BIT(RCC_APB1RSTR_SPI2RST_BIT)
#define RCC_APB1RSTR_WWDRST BIT(RCC_APB1RSTR_WWDRST_BIT)
#define RCC_APB1RSTR_TIM14RST BIT(RCC_APB1RSTR_TIM14RST_BIT)
#define RCC_APB1RSTR_TIM13RST BIT(RCC_APB1RSTR_TIM13RST_BIT)
#define RCC_APB1RSTR_TIM12RST BIT(RCC_APB1RSTR_TIM12RST_BIT)
#define RCC_APB1RSTR_TIM7RST BIT(RCC_APB1RSTR_TIM7RST_BIT)
#define RCC_APB1RSTR_TIM6RST BIT(RCC_APB1RSTR_TIM6RST_BIT)
#define RCC_APB1RSTR_TIM5RST BIT(RCC_APB1RSTR_TIM5RST_BIT)
#define RCC_APB1RSTR_TIM4RST BIT(RCC_APB1RSTR_TIM4RST_BIT)
#define RCC_APB1RSTR_TIM3RST BIT(RCC_APB1RSTR_TIM3RST_BIT)
#define RCC_APB1RSTR_TIM2RST BIT(RCC_APB1RSTR_TIM2RST_BIT)
/* AHB peripheral clock enable register */
#define RCC_AHBENR_SDIOEN_BIT 10
#define RCC_AHBENR_FSMCEN_BIT 8
#define RCC_AHBENR_CRCEN_BIT 7
#define RCC_AHBENR_FLITFEN_BIT 4
#define RCC_AHBENR_SRAMEN_BIT 2
#define RCC_AHBENR_DMA2EN_BIT 1
#define RCC_AHBENR_DMA1EN_BIT 0
#define RCC_AHBENR_SDIOEN BIT(RCC_AHBENR_SDIOEN_BIT)
#define RCC_AHBENR_FSMCEN BIT(RCC_AHBENR_FSMCEN_BIT)
#define RCC_AHBENR_CRCEN BIT(RCC_AHBENR_CRCEN_BIT)
#define RCC_AHBENR_FLITFEN BIT(RCC_AHBENR_FLITFEN_BIT)
#define RCC_AHBENR_SRAMEN BIT(RCC_AHBENR_SRAMEN_BIT)
#define RCC_AHBENR_DMA2EN BIT(RCC_AHBENR_DMA2EN_BIT)
#define RCC_AHBENR_DMA1EN BIT(RCC_AHBENR_DMA1EN_BIT)
/* APB2 peripheral clock enable register */
#define RCC_APB2ENR_TIM11EN_BIT 21
#define RCC_APB2ENR_TIM10EN_BIT 20
#define RCC_APB2ENR_TIM9EN_BIT 19
#define RCC_APB2ENR_ADC3EN_BIT 15
#define RCC_APB2ENR_USART1EN_BIT 14
#define RCC_APB2ENR_TIM8EN_BIT 13
#define RCC_APB2ENR_SPI1EN_BIT 12
#define RCC_APB2ENR_TIM1EN_BIT 11
#define RCC_APB2ENR_ADC2EN_BIT 10
#define RCC_APB2ENR_ADC1EN_BIT 9
#define RCC_APB2ENR_IOPGEN_BIT 8
#define RCC_APB2ENR_IOPFEN_BIT 7
#define RCC_APB2ENR_IOPEEN_BIT 6
#define RCC_APB2ENR_IOPDEN_BIT 5
#define RCC_APB2ENR_IOPCEN_BIT 4
#define RCC_APB2ENR_IOPBEN_BIT 3
#define RCC_APB2ENR_IOPAEN_BIT 2
#define RCC_APB2ENR_AFIOEN_BIT 0
#define RCC_APB2ENR_TIM11EN BIT(RCC_APB2ENR_TIM11EN_BIT)
#define RCC_APB2ENR_TIM10EN BIT(RCC_APB2ENR_TIM10EN_BIT)
#define RCC_APB2ENR_TIM9EN BIT(RCC_APB2ENR_TIM9EN_BIT)
#define RCC_APB2ENR_ADC3EN BIT(RCC_APB2ENR_ADC3EN_BIT)
#define RCC_APB2ENR_USART1EN BIT(RCC_APB2ENR_USART1EN_BIT)
#define RCC_APB2ENR_TIM8EN BIT(RCC_APB2ENR_TIM8EN_BIT)
#define RCC_APB2ENR_SPI1EN BIT(RCC_APB2ENR_SPI1EN_BIT)
#define RCC_APB2ENR_TIM1EN BIT(RCC_APB2ENR_TIM1EN_BIT)
#define RCC_APB2ENR_ADC2EN BIT(RCC_APB2ENR_ADC2EN_BIT)
#define RCC_APB2ENR_ADC1EN BIT(RCC_APB2ENR_ADC1EN_BIT)
#define RCC_APB2ENR_IOPGEN BIT(RCC_APB2ENR_IOPGEN_BIT)
#define RCC_APB2ENR_IOPFEN BIT(RCC_APB2ENR_IOPFEN_BIT)
#define RCC_APB2ENR_IOPEEN BIT(RCC_APB2ENR_IOPEEN_BIT)
#define RCC_APB2ENR_IOPDEN BIT(RCC_APB2ENR_IOPDEN_BIT)
#define RCC_APB2ENR_IOPCEN BIT(RCC_APB2ENR_IOPCEN_BIT)
#define RCC_APB2ENR_IOPBEN BIT(RCC_APB2ENR_IOPBEN_BIT)
#define RCC_APB2ENR_IOPAEN BIT(RCC_APB2ENR_IOPAEN_BIT)
#define RCC_APB2ENR_AFIOEN BIT(RCC_APB2ENR_AFIOEN_BIT)
/* APB1 peripheral clock enable register */
#define RCC_APB1ENR_DACEN_BIT 29
#define RCC_APB1ENR_PWREN_BIT 28
#define RCC_APB1ENR_BKPEN_BIT 27
#define RCC_APB1ENR_CANEN_BIT 25
#define RCC_APB1ENR_USBEN_BIT 23
#define RCC_APB1ENR_I2C2EN_BIT 22
#define RCC_APB1ENR_I2C1EN_BIT 21
#define RCC_APB1ENR_UART5EN_BIT 20
#define RCC_APB1ENR_UART4EN_BIT 19
#define RCC_APB1ENR_USART3EN_BIT 18
#define RCC_APB1ENR_USART2EN_BIT 17
#define RCC_APB1ENR_SPI3EN_BIT 15
#define RCC_APB1ENR_SPI2EN_BIT 14
#define RCC_APB1ENR_WWDEN_BIT 11
#define RCC_APB1ENR_TIM14EN_BIT 8
#define RCC_APB1ENR_TIM13EN_BIT 7
#define RCC_APB1ENR_TIM12EN_BIT 6
#define RCC_APB1ENR_TIM7EN_BIT 5
#define RCC_APB1ENR_TIM6EN_BIT 4
#define RCC_APB1ENR_TIM5EN_BIT 3
#define RCC_APB1ENR_TIM4EN_BIT 2
#define RCC_APB1ENR_TIM3EN_BIT 1
#define RCC_APB1ENR_TIM2EN_BIT 0
#define RCC_APB1ENR_DACEN BIT(RCC_APB1ENR_DACEN_BIT)
#define RCC_APB1ENR_PWREN BIT(RCC_APB1ENR_PWREN_BIT)
#define RCC_APB1ENR_BKPEN BIT(RCC_APB1ENR_BKPEN_BIT)
#define RCC_APB1ENR_CANEN BIT(RCC_APB1ENR_CANEN_BIT)
#define RCC_APB1ENR_USBEN BIT(RCC_APB1ENR_USBEN_BIT)
#define RCC_APB1ENR_I2C2EN BIT(RCC_APB1ENR_I2C2EN_BIT)
#define RCC_APB1ENR_I2C1EN BIT(RCC_APB1ENR_I2C1EN_BIT)
#define RCC_APB1ENR_UART5EN BIT(RCC_APB1ENR_UART5EN_BIT)
#define RCC_APB1ENR_UART4EN BIT(RCC_APB1ENR_UART4EN_BIT)
#define RCC_APB1ENR_USART3EN BIT(RCC_APB1ENR_USART3EN_BIT)
#define RCC_APB1ENR_USART2EN BIT(RCC_APB1ENR_USART2EN_BIT)
#define RCC_APB1ENR_SPI3EN BIT(RCC_APB1ENR_SPI3EN_BIT)
#define RCC_APB1ENR_SPI2EN BIT(RCC_APB1ENR_SPI2EN_BIT)
#define RCC_APB1ENR_WWDEN BIT(RCC_APB1ENR_WWDEN_BIT)
#define RCC_APB1ENR_TIM14EN BIT(RCC_APB1ENR_TIM14EN_BIT)
#define RCC_APB1ENR_TIM13EN BIT(RCC_APB1ENR_TIM13EN_BIT)
#define RCC_APB1ENR_TIM12EN BIT(RCC_APB1ENR_TIM12EN_BIT)
#define RCC_APB1ENR_TIM7EN BIT(RCC_APB1ENR_TIM7EN_BIT)
#define RCC_APB1ENR_TIM6EN BIT(RCC_APB1ENR_TIM6EN_BIT)
#define RCC_APB1ENR_TIM5EN BIT(RCC_APB1ENR_TIM5EN_BIT)
#define RCC_APB1ENR_TIM4EN BIT(RCC_APB1ENR_TIM4EN_BIT)
#define RCC_APB1ENR_TIM3EN BIT(RCC_APB1ENR_TIM3EN_BIT)
#define RCC_APB1ENR_TIM2EN BIT(RCC_APB1ENR_TIM2EN_BIT)
/* Backup domain control register */
#define RCC_BDCR_BDRST_BIT 16
#define RCC_BDCR_RTCEN_BIT 15
#define RCC_BDCR_LSEBYP_BIT 2
#define RCC_BDCR_LSERDY_BIT 1
#define RCC_BDCR_LSEON_BIT 0
#define RCC_BDCR_BDRST BIT(RCC_BDCR_BDRST_BIT)
#define RCC_BDCR_RTCEN BIT(RCC_BDCR_RTC_BIT)
#define RCC_BDCR_RTCSEL (0x3 << 8)
#define RCC_BDCR_RTCSEL_NONE (0x0 << 8)
#define RCC_BDCR_RTCSEL_LSE (0x1 << 8)
#define RCC_BDCR_RTCSEL_LSI (0x2 << 8)
#define RCC_BDCR_RTCSEL_HSE (0x3 << 8)
#define RCC_BDCR_LSEBYP BIT(RCC_BDCR_LSEBYP_BIT)
#define RCC_BDCR_LSERDY BIT(RCC_BDCR_LSERDY_BIT)
#define RCC_BDCR_LSEON BIT(RCC_BDCR_LSEON_BIT)
/* Control/status register */
#define RCC_CSR_LPWRRSTF_BIT 31
#define RCC_CSR_WWDGRSTF_BIT 30
#define RCC_CSR_IWDGRSTF_BIT 29
#define RCC_CSR_SFTRSTF_BIT 28
#define RCC_CSR_PORRSTF_BIT 27
#define RCC_CSR_PINRSTF_BIT 26
#define RCC_CSR_RMVF_BIT 24
#define RCC_CSR_LSIRDY_BIT 1
#define RCC_CSR_LSION_BIT 0
#define RCC_CSR_LPWRRSTF BIT(RCC_CSR_LPWRRSTF_BIT)
#define RCC_CSR_WWDGRSTF BIT(RCC_CSR_WWDGRSTF_BIT)
#define RCC_CSR_IWDGRSTF BIT(RCC_CSR_IWDGRSTF_BIT)
#define RCC_CSR_SFTRSTF BIT(RCC_CSR_SFTRSTF_BIT)
#define RCC_CSR_PORRSTF BIT(RCC_CSR_PORRSTF_BIT)
#define RCC_CSR_PINRSTF BIT(RCC_CSR_PINRSTF_BIT)
#define RCC_CSR_RMVF BIT(RCC_CSR_RMVF_BIT)
#define RCC_CSR_LSIRDY BIT(RCC_CSR_LSIRDY_BIT)
#define RCC_CSR_LSION BIT(RCC_CSR_LSION_BIT)
/*
* Convenience routines
*/
/**
* SYSCLK sources
* @see rcc_clk_init()
*/
typedef enum rcc_sysclk_src {
RCC_CLKSRC_HSI = 0x0,
RCC_CLKSRC_HSE = 0x1,
RCC_CLKSRC_PLL = 0x2,
} rcc_sysclk_src;
/**
* PLL entry clock source
* @see rcc_clk_init()
*/
typedef enum rcc_pllsrc {
RCC_PLLSRC_HSE = (0x1 << 16),
RCC_PLLSRC_HSI_DIV_2 = (0x0 << 16)
} rcc_pllsrc;
/**
* PLL multipliers
* @see rcc_clk_init()
*/
typedef enum rcc_pll_multiplier {
RCC_PLLMUL_2 = (0x0 << 18),
RCC_PLLMUL_3 = (0x1 << 18),
RCC_PLLMUL_4 = (0x2 << 18),
RCC_PLLMUL_5 = (0x3 << 18),
RCC_PLLMUL_6 = (0x4 << 18),
RCC_PLLMUL_7 = (0x5 << 18),
RCC_PLLMUL_8 = (0x6 << 18),
RCC_PLLMUL_9 = (0x7 << 18),
RCC_PLLMUL_10 = (0x8 << 18),
RCC_PLLMUL_11 = (0x9 << 18),
RCC_PLLMUL_12 = (0xA << 18),
RCC_PLLMUL_13 = (0xB << 18),
RCC_PLLMUL_14 = (0xC << 18),
RCC_PLLMUL_15 = (0xD << 18),
RCC_PLLMUL_16 = (0xE << 18),
} rcc_pll_multiplier;
/**
* @brief Identifies bus and clock line for a peripheral.
*
* Also generally useful as a unique identifier for that peripheral
* (or its corresponding device struct).
*/
typedef enum rcc_clk_id {
RCC_GPIOA,
RCC_GPIOB,
RCC_GPIOC,
RCC_GPIOD,
// RCC_AFIO,
RCC_ADC1,
RCC_ADC2,
RCC_ADC3,
RCC_USART1,
RCC_USART2,
RCC_USART3,
RCC_TIMER1,
RCC_TIMER2,
RCC_TIMER3,
RCC_TIMER4,
RCC_SPI1,
RCC_SPI2,
RCC_DMA1,
RCC_PWR,
RCC_BKP,
RCC_I2C1,
RCC_I2C2,
RCC_CRC,
// RCC_FLITF,
// RCC_SRAM,
RCC_GPIOE,
RCC_GPIOF,
RCC_GPIOG,
RCC_UART4,
RCC_UART5,
RCC_TIMER5,
RCC_TIMER6,
RCC_TIMER7,
RCC_TIMER8,
RCC_FSMC,
RCC_DAC,
RCC_DMA2,
RCC_SDIO,
RCC_SPI3,
RCC_TIMER9,
RCC_TIMER10,
RCC_TIMER11,
RCC_TIMER12,
RCC_TIMER13,
RCC_TIMER14,
RCC_USBFS,
RCC_SYSCFG,
RCC_SPI4
} rcc_clk_id;
void rcc_clk_init(rcc_sysclk_src sysclk_src,
rcc_pllsrc pll_src,
rcc_pll_multiplier pll_mul);
void rcc_clk_disable(rcc_clk_id device);
void rcc_clk_enable(rcc_clk_id device);
void rcc_reset_dev(rcc_clk_id device);
void SetupClock72MHz();
void SetupClock120MHz();
void SetupClock168MHz();
typedef enum rcc_clk_domain {
RCC_APB1,
RCC_APB2,
RCC_AHB1,
RCC_AHB2,
RCC_AHB3
} rcc_clk_domain;
rcc_clk_domain rcc_dev_clk(rcc_clk_id device);
uint32 rcc_dev_clk_speed(rcc_clk_id id);
uint32 rcc_dev_timer_clk_speed(rcc_clk_id id);
/**
* Prescaler identifiers
* @see rcc_set_prescaler()
*/
typedef enum rcc_prescaler {
RCC_PRESCALER_AHB,
RCC_PRESCALER_APB1,
RCC_PRESCALER_APB2,
RCC_PRESCALER_USB,
RCC_PRESCALER_ADC
} rcc_prescaler;
/**
* ADC prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_adc_divider {
RCC_ADCPRE_PCLK_DIV_2 = 0x0 << 14,
RCC_ADCPRE_PCLK_DIV_4 = 0x1 << 14,
RCC_ADCPRE_PCLK_DIV_6 = 0x2 << 14,
RCC_ADCPRE_PCLK_DIV_8 = 0x3 << 14,
} rcc_adc_divider;
/**
* APB1 prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_apb1_divider {
RCC_APB1_HCLK_DIV_1 = 0x0 << 8,
RCC_APB1_HCLK_DIV_2 = 0x4 << 8,
RCC_APB1_HCLK_DIV_4 = 0x5 << 8,
RCC_APB1_HCLK_DIV_8 = 0x6 << 8,
RCC_APB1_HCLK_DIV_16 = 0x7 << 8,
} rcc_apb1_divider;
/**
* APB2 prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_apb2_divider {
RCC_APB2_HCLK_DIV_1 = 0x0 << 11,
RCC_APB2_HCLK_DIV_2 = 0x4 << 11,
RCC_APB2_HCLK_DIV_4 = 0x5 << 11,
RCC_APB2_HCLK_DIV_8 = 0x6 << 11,
RCC_APB2_HCLK_DIV_16 = 0x7 << 11,
} rcc_apb2_divider;
/**
* AHB prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_ahb_divider {
RCC_AHB_SYSCLK_DIV_1 = 0x0 << 4,
RCC_AHB_SYSCLK_DIV_2 = 0x8 << 4,
RCC_AHB_SYSCLK_DIV_4 = 0x9 << 4,
RCC_AHB_SYSCLK_DIV_8 = 0xA << 4,
RCC_AHB_SYSCLK_DIV_16 = 0xB << 4,
RCC_AHB_SYSCLK_DIV_32 = 0xC << 4,
RCC_AHB_SYSCLK_DIV_64 = 0xD << 4,
RCC_AHB_SYSCLK_DIV_128 = 0xD << 4,
RCC_AHB_SYSCLK_DIV_256 = 0xE << 4,
RCC_AHB_SYSCLK_DIV_512 = 0xF << 4,
} rcc_ahb_divider;
void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider);
/**
* @brief Start the low speed internal oscillatior
*/
static inline void rcc_start_lsi(void) {
*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSION_BIT) = 1;
while (*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSIRDY_BIT) == 0);
}
/* FIXME [0.0.13] Just have data point to an rcc_pll_multiplier! */
/**
* @brief Start the low speed external oscillatior
*/
static inline void rcc_start_lse(void) {
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEBYP_BIT, 0);
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEON_BIT, 1);
while (bb_peri_get_bit(&RCC_BASE->BDCR, RCC_BDCR_LSERDY_BIT ) == 0);
}
/*
* Deprecated bits.
*/
static inline void rcc_start_hse(void) { // Added to support RTClock
// *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1;
while (bb_peri_get_bit(&RCC_BASE->CR, RCC_CR_HSERDY_BIT) == 0);
}
#ifdef __cplusplus
} // extern "C"
#endif
#endif

View File

@ -0,0 +1,264 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file black_f4.cpp
* @author ala42
* @brief black_f4 board file.
*/
#ifdef BOARD_black_f4
#include "black_f4.h"
//#include "fsmc.h"
#include "gpio.h"
#include "rcc.h"
#include "timer.h"
#include "wirish_types.h"
// Pins reserved for the on-board hardware
#define USB_DM_PIN BOARD_USB_DM_PIN // PA11
#define USB_DP_PIN BOARD_USB_DP_PIN // PA12
#define FLASH_CS_PIN PB0
#define FLASH_CLK_PIN BOARD_SPI3_SCK_PIN // PB3
#define FLASH_DO_PIN BOARD_SPI3_MISO_PIN // PB4
#define FLASH_DI_PIN BOARD_SPI3_MOSI_PIN // PB5
#define NRF24_CLK_PIN BOARD_SPI3_SCK_PIN // PB3
#define NRF24_DO_PIN BOARD_SPI3_MISO_PIN // PB4
#define NRF24_DI_PIN BOARD_SPI3_MOSI_PIN // PB5
#define NRF24_CE_PIN PB6
#define NRF24_CS_PIN PB7
#define NRF24_IRQ_PIN PB8
// SD card, SDIO mode
#define SD_DAT0 BOARD_SDIO_D0 // PC8
#define SD_DAT1 BOARD_SDIO_D1 // PC9
#define SD_DAT2 BOARD_SDIO_D2 // PC10
#define SD_DAT3 BOARD_SDIO_D3 // PC11
#define SD_CLK BOARD_SDIO_CK // PC12
#define SD_CMD BOARD_SDIO_CMD // PD2
// SD card, SPI mode, only usable with software SPI
#define SD_DI BOARD_SDIO_CMD // PD2
#define SD_DO BOARD_SDIO_D0 // PC8
#define SD_CS BOARD_SDIO_D3 // PC11
#define SD_SCLK BOARD_SDIO_CK // PC12
//static void initSRAMChip(void);
/*****************************************************************************/
// Alternate functions, see DocID022152 Rev 8, Table 9.
/*****************************************************************************/
void boardInit(void) {
/* // remap TIMER8 to PC6-9
gpio_set_af_mode(GPIOC, 6, 3);
gpio_set_af_mode(GPIOC, 7, 3);
gpio_set_af_mode(GPIOC, 8, 3);
gpio_set_af_mode(GPIOC, 9, 3);
// remap TIMER1 to PE9,11,13,14
gpio_set_af_mode(GPIOE, 9, 1);
gpio_set_af_mode(GPIOE, 11, 1);
gpio_set_af_mode(GPIOE, 13, 1);
gpio_set_af_mode(GPIOE, 14, 1);
// remap TIMER3 to PB4,5,0,1
gpio_set_af_mode(GPIOB, 4, 2);
gpio_set_af_mode(GPIOB, 5, 2);
gpio_set_af_mode(GPIOB, 0, 2);
gpio_set_af_mode(GPIOB, 1, 2);
//gpio_set_af_mode(GPIOA, 2, 7);
//gpio_set_af_mode(GPIOA, 3, 7);
*/
return;
}
/*
typedef struct stm32_pin_info {
gpio_dev *gpio_device; // Maple pin's GPIO device
uint8 gpio_bit; // Pin's GPIO port bit.
timer_dev *timer_device; // Pin's timer device, if any.
uint8 timer_channel; // Timer channel, or 0 if none.
const adc_dev *adc_device; // ADC device, if any.
uint8 adc_channel; // Pin ADC channel, or ADCx if none.
} stm32_pin_info;
*/
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { // LQFP100 package pin
{GPIOA, 0, TIMER5, 1, ADC1, 0}, // D00/PA0 | 23 | USART2_CTS | UART4_TX | ETH_MII_CRS | TIM2_CH1_ETR | TIM5_CH1 | TIM8_ETR | ADC123_IN0/WKUP
{GPIOA, 1, TIMER5, 2, ADC1, 1}, // D01/PA1 | 24 | USART2_RTS | UART4_RX | ETH_RMII_REF_CLK | ETH_MII_RX_CLK | TIM5_CH2 | TIM2_CH2 | ADC123_IN1
{GPIOA, 2, TIMER5, 3, ADC1, 2}, // D02/PA2 | 25 | USART2_TX | TIM5_CH3 | TIM9_CH1 | TIM2_CH3 | ETH_MDIO | ADC123_IN2
{GPIOA, 3, TIMER5, 4, ADC1, 3}, // D03/PA3 | 26 | USART2_RX | TIM5_CH4 | TIM9_CH2 | TIM2_CH4 | OTG_HS_ULPI_D0 | ETH_MII_COL | ADC123_IN3
{GPIOA, 4, NULL, 0, ADC1, 4}, // D04/PA4 | 29 | SPI1_NSS | SPI3_NSS | USART2_CK | DCMI_HSYNC | OTG_HS_SOF | I2S3_WS | ADC12_IN4 / DAC_OUT1
{GPIOA, 5, NULL, 0, ADC1, 5}, // D05/PA5 | 30 | SPI1_SCK | OTG_HS_ULPI_CK | TIM2_CH1_ETR | TIM8_CH1N | ADC12_IN5 / DAC_OUT2
{GPIOA, 6, NULL, 1, ADC1, 6}, // D06/PA6 | 31 | SPI1_MISO | TIM8_BKIN | TIM13_CH1 | DCMI_PIXCLK | TIM3_CH1 | TIM1_BKIN | ADC12_IN6
{GPIOA, 7, NULL, 0, ADC1, 7}, // D07/PA7 | 32 | SPI1_MOSI | TIM8_CH1N | TIM14_CH1 | TIM3_CH2 | ETH_MII_RX_DV | TIM1_CH1N / ETH_RMII_CRS_DV | ADC12_IN7
{GPIOA, 8, NULL, 0, NULL, ADCx}, // D08/PA8 | 67 | MCO1 | USART1_CK | TIM1_CH1 | I2C3_SCL | OTG_FS_SOF
{GPIOA, 9, NULL, 0, NULL, ADCx}, // D09/PA9 | 68 | USART1_TX | TIM1_CH2 | I2C3_SMBA | DCMI_D0
{GPIOA, 10, NULL, 0, NULL, ADCx}, // D10/PA10 | 69 | USART1_RX | TIM1_CH3 | OTG_FS_ID | DCMI_D1
{GPIOA, 11, NULL, 0, NULL, ADCx}, // D11/PA11 | 70 | USART1_CTS | CAN1_RX | TIM1_CH4 | OTG_FS_DM
{GPIOA, 12, NULL, 0, NULL, ADCx}, // D12/PA12 | 71 | USART1_RTS | CAN1_TX | TIM1_ETR | OTG_FS_DP
{GPIOA, 13, NULL, 0, NULL, ADCx}, // D13/PA13 | 72 | JTMS-SWDIO
{GPIOA, 14, NULL, 0, NULL, ADCx}, // D14/PA14 | 76 | JTCK-SWCLK
{GPIOA, 15, TIMER2, 1, NULL, ADCx}, // D15/PA15 | 77 | JTDI | SPI3_NSS | I2S3_WS | TIM2_CH1_ETR | SPI1_NSS
{GPIOB, 0, TIMER3, 3, ADC1, 8}, // D16/PB0 | 35 | TIM3_CH3 | TIM8_CH2N | OTG_HS_ULPI_D1 | ETH_MII_RXD2 | TIM1_CH2N | ADC12_IN8
{GPIOB, 1, TIMER3, 4, ADC1, 9}, // D17/PB1 | 36 | TIM3_CH4 | TIM8_CH3N | OTG_HS_ULPI_D2 | ETH_MII_RXD3 | TIM1_CH3N | ADC12_IN9
{GPIOB, 2, NULL, 0, NULL, ADCx}, // D18/PB2 | 37 | BOOT1
{GPIOB, 3, TIMER2, 2, NULL, ADCx}, // D19/PB3 | 89 | JTDO | TRACESWO | SPI3_SCK | I2S3_CK | TIM2_CH2 | SPI1_SCK
{GPIOB, 4, TIMER3, 1, NULL, ADCx}, // D20/PB4 | 90 | NJTRST | SPI3_MISO | TIM3_CH1 | SPI1_MISO | I2S3ext_SD
{GPIOB, 5, TIMER3, 2, NULL, ADCx}, // D21/PB5 | 91 | I2C1_SMBA | CAN2_RX | OTG_HS_ULPI_D7 | ETH_PPS_OUT | TIM3_CH2 | SPI1_MOSI | SPI3_MOSI | DCMI_D10 | I2S3_SD
{GPIOB, 6, NULL, 0, NULL, ADCx}, // D22/PB6 | 92 | I2C1_SCL | TIM4_CH1 | CAN2_TX | DCMI_D5 | USART1_TX
{GPIOB, 7, NULL, 0, NULL, ADCx}, // D23/PB7 | 93 | I2C1_SDA | FSMC_NL | DCMI_VSYNC | USART1_RX | TIM4_CH2
{GPIOB, 8, NULL, 0, NULL, ADCx}, // D24/PB8 | 95 | TIM4_CH3 | SDIO_D4 | TIM10_CH1 | DCMI_D6 | ETH_MII_TXD3 | I2C1_SCL | CAN1_RX
{GPIOB, 9, NULL, 0, NULL, ADCx}, // D25/PB9 | 96 | SPI2_NSS | I2S2_WS | TIM4_CH4 | TIM11_CH1 | SDIO_D5 | DCMI_D7 | I2C1_SDA | CAN1_TX
{GPIOB, 10, NULL, 0, NULL, ADCx}, // D26/PB10 | 47 | SPI2_SCK | I2S2_CK | I2C2_SCL | USART3_TX | OTG_HS_ULPI_D3 | ETH_MII_RX_ER | TIM2_CH3
{GPIOB, 11, NULL, 0, NULL, ADCx}, // D27/PB11 | 48 | I2C2_SDA | USART3_RX | OTG_HS_ULPI_D4 | ETH_RMII_TX_EN | ETH_MII_TX_EN | TIM2_CH4
{GPIOB, 12, NULL, 0, NULL, ADCx}, // D28/PB12 | 51 | SPI2_NSS | I2S2_WS | I2C2_SMBA | USART3_CK | TIM1_BKIN | CAN2_RX | OTG_HS_ULPI_D5 | ETH_RMII_TXD0 | ETH_MII_TXD0 | OTG_HS_ID
{GPIOB, 13, NULL, 0, NULL, ADCx}, // D29/PB13 | 52 | SPI2_SCK | I2S2_CK | USART3_CTS | TIM1_CH1N | CAN2_TX | OTG_HS_ULPI_D6 | ETH_RMII_TXD1 | ETH_MII_TXD1
{GPIOB, 14, NULL, 0, NULL, ADCx}, // D30/PB14 | 53 | SPI2_MISO | TIM1_CH2N | TIM12_CH1 | OTG_HS_DM | USART3_RTS | TIM8_CH2N | I2S2ext_SD
{GPIOB, 15, NULL, 0, NULL, ADCx}, // D31/PB15 | 54 | SPI2_MOSI | I2S2_SD | TIM1_CH3N | TIM8_CH3N | TIM12_CH2 | OTG_HS_DP
{GPIOC, 0, NULL, 0, ADC1, 10}, // D32/PC0 | 15 | OTG_HS_ULPI_STP | ADC123_IN10
{GPIOC, 1, NULL, 0, ADC1, 11}, // D33/PC1 | 16 | ETH_MDC | ADC123_IN11
{GPIOC, 2, NULL, 0, ADC1, 12}, // D34/PC2 | 17 | SPI2_MISO | OTG_HS_ULPI_DIR | ETH_MII_TXD2 | I2S2ext_SD | ADC123_IN12
{GPIOC, 3, NULL, 0, ADC1, 13}, // D35/PC3 | 18 | SPI2_MOSI | I2S2_SD | OTG_HS_ULPI_NXT | ETH_MII_TX_CLK | ADC123_IN13
{GPIOC, 4, NULL, 0, ADC1, 14}, // D36/PC4 | 33 | ETH_RMII_RX_D0 | ETH_MII_RX_D0 | ADC12_IN14
{GPIOC, 5, NULL, 0, ADC1, 15}, // D37/PC5 | 34 | ETH_RMII_RX_D1 | ETH_MII_RX_D1 | ADC12_IN15
{GPIOC, 6, TIMER8, 1, NULL, ADCx}, // D38/PC6 | 63 | I2S2_MCK | TIM8_CH1/SDIO_D6 | USART6_TX | DCMI_D0/TIM3_CH1
{GPIOC, 7, TIMER8, 2, NULL, ADCx}, // D39/PC7 | 64 | I2S3_MCK | TIM8_CH2/SDIO_D7 | USART6_RX | DCMI_D1/TIM3_CH2
{GPIOC, 8, TIMER8, 3, NULL, ADCx}, // D40/PC8 | 65 | TIM8_CH3 | SDIO_D0 | TIM3_CH3 | USART6_CK | DCMI_D2
{GPIOC, 9, TIMER8, 4, NULL, ADCx}, // D41/PC9 | 66 | I2S_CKIN | MCO2 | TIM8_CH4 | SDIO_D1 | I2C3_SDA | DCMI_D3 | TIM3_CH4
{GPIOC, 10, NULL, 0, NULL, ADCx}, // D42/PC10 | 78 | SPI3_SCK | I2S3_CK | UART4_TX | SDIO_D2 | DCMI_D8 | USART3_TX
{GPIOC, 11, NULL, 0, NULL, ADCx}, // D43/PC11 | 79 | UART4_RX | SPI3_MISO | SDIO_D3 | DCMI_D4 | USART3_RX | I2S3ext_SD
{GPIOC, 12, NULL, 0, NULL, ADCx}, // D44/PC12 | 80 | UART5_TX | SDIO_CK | DCMI_D9 | SPI3_MOSI | I2S3_SD | USART3_CK
{GPIOC, 13, NULL, 0, NULL, ADCx}, // D45/PC13 | 7 | RTC_OUT, RTC_TAMP1, RTC_TS
{GPIOC, 14, NULL, 0, NULL, ADCx}, // D46/PC14 | 8 | OSC32_IN
{GPIOC, 15, NULL, 0, NULL, ADCx}, // D47/PC15 | 9 | OSC32_OUT
{GPIOD, 0, NULL, 0, NULL, ADCx}, // D48/PD0 | 81 | FSMC_D2 | CAN1_RX
{GPIOD, 1, NULL, 0, NULL, ADCx}, // D49/PD1 | 82 | FSMC_D3 | CAN1_TX
{GPIOD, 2, NULL, 0, NULL, ADCx}, // D50/PD2 | 83 | TIM3_ETR | UART5_RX | SDIO_CMD | DCMI_D11
{GPIOD, 3, NULL, 0, NULL, ADCx}, // D51/PD3 | 84 | FSMC_CLK | USART2_CTS
{GPIOD, 4, NULL, 0, NULL, ADCx}, // D52/PD4 | 85 | FSMC_NOE | USART2_RTS
{GPIOD, 5, NULL, 0, NULL, ADCx}, // D53/PD5 | 86 | FSMC_NWE | USART2_TX
{GPIOD, 6, NULL, 0, NULL, ADCx}, // D54/PD6 | 87 | FSMC_NWAIT | USART2_RX
{GPIOD, 7, NULL, 0, NULL, ADCx}, // D55/PD7 | 88 | USART2_CK | FSMC_NE1 | FSMC_NCE2
{GPIOD, 8, NULL, 0, NULL, ADCx}, // D56/PD8 | 55 | FSMC_D13 | USART3_TX
{GPIOD, 9, NULL, 0, NULL, ADCx}, // D57/PD9 | 56 | FSMC_D14 | USART3_RX
{GPIOD, 10, NULL, 0, NULL, ADCx}, // D58/PD10 | 57 | FSMC_D15 | USART3_CK
{GPIOD, 11, NULL, 0, NULL, ADCx}, // D59/PD11 | 58 | FSMC_CLE | FSMC_A16 | USART3_CTS
{GPIOD, 12, TIMER4, 1, NULL, ADCx}, // D60/PD12 | 59 | FSMC_ALE | FSMC_A17 | TIM4_CH1 | USART3_RTS // remap in
{GPIOD, 13, TIMER4, 2, NULL, ADCx}, // D61/PD13 | 60 | FSMC_A18 | TIM4_CH2 // remap in
{GPIOD, 14, TIMER4, 3, NULL, ADCx}, // D62/PD14 | 61 | FSMC_D0 | TIM4_CH3 // remap in
{GPIOD, 15, TIMER4, 4, NULL, ADCx}, // D63/PD15 | 62 | FSMC_D1 | TIM4_CH4 // remap in
{GPIOE, 0, NULL, 0, NULL, ADCx}, // D64/PE0 | 97 | TIM4_ETR | FSMC_NBL0 | DCMI_D2
{GPIOE, 1, NULL, 0, NULL, ADCx}, // D65/PE1 | 98 | FSMC_NBL1 | DCMI_D3
{GPIOE, 2, NULL, 0, NULL, ADCx}, // D66/PE2 | 1 | TRACECLK | FSMC_A23 | ETH_MII_TXD3
{GPIOE, 3, NULL, 0, NULL, ADCx}, // D67/PE3 | 2 | TRACED0 | FSMC_A19
{GPIOE, 4, NULL, 0, NULL, ADCx}, // D68/PE4 | 3 | TRACED1 | FSMC_A20 | DCMI_D4
{GPIOE, 5, NULL, 0, NULL, ADCx}, // D69/PE5 | 4 | TRACED2 | FSMC_A21 | TIM9_CH1 / DCMI_D6
{GPIOE, 6, NULL, 0, NULL, ADCx}, // D70/PE6 | 5 | TRACED3 | FSMC_A22 | TIM9_CH2 / DCMI_D7
{GPIOE, 7, NULL, 0, NULL, ADCx}, // D71/PE7 | 38 | FSMC_D4 | TIM1_ETR
{GPIOE, 8, NULL, 0, NULL, ADCx}, // D72/PE8 | 39 | FSMC_D5 | TIM1_CH1N
{GPIOE, 9, TIMER1, 1, NULL, ADCx}, // D73/PE9 | 40 | FSMC_D6 | TIM1_CH1 // remap in
{GPIOE, 10, NULL, 0, NULL, ADCx}, // D74/PE10 | 41 | FSMC_D7 | TIM1_CH2N
{GPIOE, 11, TIMER1, 2, NULL, ADCx}, // D75/PE11 | 42 | FSMC_D8 | TIM1_CH2 // remap in
{GPIOE, 12, NULL, 0, NULL, ADCx}, // D76/PE12 | 43 | FSMC_D9 | TIM1_CH3N
{GPIOE, 13, TIMER1, 3, NULL, ADCx}, // D77/PE13 | 44 | FSMC_D10 | TIM1_CH3 // remap in
{GPIOE, 14, TIMER1, 4, NULL, ADCx}, // D78/PE14 | 45 | FSMC_D11 | TIM1_CH4 // remap in
{GPIOE, 15, NULL, 0, NULL, ADCx}, // D79/PE15 | 46 | FSMC_D12 | TIM1_BKIN
#if 0
{GPIOF, 0, NULL, 0, NULL, ADCx}, // D80/PF0
{GPIOF, 1, NULL, 0, NULL, ADCx}, // D81/PF1
{GPIOF, 2, NULL, 0, NULL, ADCx}, // D82/PF2
{GPIOF, 3, NULL, 0, NULL, ADCx}, // D83/PF3
{GPIOF, 4, NULL, 0, NULL, ADCx}, // D84/PF4
{GPIOF, 5, NULL, 0, NULL, ADCx}, // D85/PF5
{GPIOF, 6, NULL, 0, NULL, ADCx}, // D86/PF6
{GPIOF, 7, NULL, 0, NULL, ADCx}, // D87/PF7
{GPIOF, 8, NULL, 0, NULL, ADCx}, // D88/PF8
{GPIOF, 9, NULL, 0, NULL, ADCx}, // D89/PF9
{GPIOF, 10, NULL, 0, NULL, ADCx}, // D90/PF10
{GPIOF, 11, NULL, 0, NULL, ADCx}, // D91/PF11
{GPIOF, 12, NULL, 0, NULL, ADCx}, // D92/PF12
{GPIOF, 13, NULL, 0, NULL, ADCx}, // D93/PF13
{GPIOF, 14, NULL, 0, NULL, ADCx}, // D94/PF14
{GPIOF, 15, NULL, 0, NULL, ADCx}, // D95/PF15
{GPIOG, 0, NULL, 0, NULL, ADCx}, // D96/PG0
{GPIOG, 1, NULL, 0, NULL, ADCx}, // D97/PG1
{GPIOG, 2, NULL, 0, NULL, ADCx}, // D98/PG2
{GPIOG, 3, NULL, 0, NULL, ADCx}, // D99/PG3
{GPIOG, 4, NULL, 0, NULL, ADCx}, // D100/PG4
{GPIOG, 5, NULL, 0, NULL, ADCx}, // D101/PG5
{GPIOG, 6, NULL, 0, NULL, ADCx}, // D102/PG6
{GPIOG, 7, NULL, 0, NULL, ADCx}, // D103/PG7
{GPIOG, 8, NULL, 0, NULL, ADCx}, // D104/PG8
{GPIOG, 9, NULL, 0, NULL, ADCx}, // D105/PG9
{GPIOG, 10, NULL, 0, NULL, ADCx}, // D106/PG10
{GPIOG, 11, NULL, 0, NULL, ADCx}, // D107/PG11
{GPIOG, 12, NULL, 0, NULL, ADCx}, // D108/PG12
{GPIOG, 13, NULL, 0, NULL, ADCx}, // D109/PG13
{GPIOG, 14, NULL, 0, NULL, ADCx}, // D110/PG14
{GPIOG, 15, NULL, 0, NULL, ADCx} // D111/PG15
#endif
};
/* to be defined
extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = {
0, 1, 2, 3, 15, 16, 17, 19, 20, 21, 38, 39, 49, 41, 60, 61, 62, 63, 73, 75, 77, 78
};
*/
extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = {
PA0, PA1, PA2, PA3, PA4, PA5, PA6, PA7, PB0, PB1, PC0, PC1, PC2, PC3, PC4, PC5
};
extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = {
BOARD_LED_PIN, BOARD_LED2_PIN, BOARD_BUTTON1_PIN, BOARD_BUTTON2_PIN, BOARD_BUTTON2_PIN,
BOARD_JTMS_SWDIO_PIN, BOARD_JTCK_SWCLK_PIN,
FLASH_CS_PIN, FLASH_CLK_PIN, FLASH_DO_PIN, FLASH_DI_PIN,
NRF24_CE_PIN, NRF24_CS_PIN, NRF24_IRQ_PIN,
BOARD_SDIO_D0, BOARD_SDIO_D1, BOARD_SDIO_D2, BOARD_SDIO_D3, BOARD_SDIO_CK, BOARD_SDIO_CMD,
USB_DM_PIN, USB_DP_PIN
};
/*
static void initSRAMChip(void) {
fsmc_nor_psram_reg_map *regs = FSMC_NOR_PSRAM1_BASE;
fsmc_sram_init_gpios();
rcc_clk_enable(RCC_FSMC);
regs->BCR = (FSMC_BCR_WREN | FSMC_BCR_MWID_16BITS | FSMC_BCR_MTYP_SRAM |
FSMC_BCR_MBKEN);
fsmc_nor_psram_set_addset(regs, 0);
fsmc_nor_psram_set_datast(regs, 3);
}
*/
#endif

View File

@ -0,0 +1,130 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file black_f4.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Private include file for Maple Native in boards.h
*
* See maple.h for more information on these definitions.
*/
#ifndef _BOARD_BLACK_F4_H_
#define _BOARD_BLACK_F4_H_
#define Port2Pin(port, bit) ((port-'A')*16+bit)
#define CYCLES_PER_MICROSECOND 168
#undef STM32_PCLK1
#undef STM32_PCLK2
#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4)
#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2)
#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1)
#define BOARD_USB_DM_PIN PA11
#define BOARD_USB_DP_PIN PA12
#define BOARD_LED_PIN PA6 //Port2Pin('A', 6)
#define BOARD_LED2_PIN PA7 //Port2Pin('A', 7)
#define BOARD_BUTTON1_PIN PA0 //Port2Pin('A', 0)
#define BOARD_BUTTON2_PIN PE4 //Port2Pin('E', 4)
#define BOARD_BUTTON3_PIN PE3 //Port2Pin('E', 3)
#define BOARD_NR_USARTS 5
#define BOARD_USART1_TX_PIN PA9 //Port2Pin('A', 9)
#define BOARD_USART1_RX_PIN PA10 //Port2Pin('A',10)
#define BOARD_USART2_TX_PIN PA2 //Port2Pin('A', 2)
#define BOARD_USART2_RX_PIN PA3 //Port2Pin('A', 3)
#define BOARD_USART3_TX_PIN PB10 //Port2Pin('B',10)
#define BOARD_USART3_RX_PIN PB11 //Port2Pin('B',11)
#define BOARD_UART4_TX_PIN PA0 //Port2Pin('A', 0)
#define BOARD_UART4_RX_PIN PA1 //Port2Pin('A', 1)
#define BOARD_UART5_TX_PIN PC12 //Port2Pin('C',12)
#define BOARD_UART5_RX_PIN PD2 //Port2Pin('D', 2)
#define BOARD_NR_SPI 3
#define BOARD_SPI1_NSS_PIN PA4 //Port2Pin('A', 4)
#define BOARD_SPI1_SCK_PIN PA5 //Port2Pin('A', 5)
#define BOARD_SPI1_MISO_PIN PA6 //Port2Pin('A', 6)
#define BOARD_SPI1_MOSI_PIN PA7 //Port2Pin('A', 7)
#define BOARD_SPI1A_NSS_PIN PA15 //Port2Pin('A',15)
#define BOARD_SPI1A_SCK_PIN PB3 //Port2Pin('B', 3)
#define BOARD_SPI1A_MISO_PIN PB4 //Port2Pin('B', 4)
#define BOARD_SPI1A_MOSI_PIN PB5 //Port2Pin('B', 5)
#define BOARD_SPI2_NSS_PIN PB12 //Port2Pin('B',12)
#define BOARD_SPI2_SCK_PIN PB13 //Port2Pin('B',13)
#define BOARD_SPI2_MISO_PIN PB14 //Port2Pin('B',14)
#define BOARD_SPI2_MOSI_PIN PB15 //Port2Pin('B',15)
#define BOARD_SPI2A_NSS_PIN PB9 //Port2Pin('B', 9)
#define BOARD_SPI2A_SCK_PIN PB10 //Port2Pin('B',10)
#define BOARD_SPI2A_MISO_PIN PC2 //Port2Pin('C', 2)
#define BOARD_SPI2A_MOSI_PIN pc3 //Port2Pin('C', 3)
#define BOARD_SPI3_NSS_PIN PA15 //Port2Pin('A',15)
#define BOARD_SPI3_SCK_PIN PB3 //Port2Pin('B', 3)
#define BOARD_SPI3_MISO_PIN PB4 //Port2Pin('B', 4)
#define BOARD_SPI3_MOSI_PIN PB5 //Port2Pin('B', 5)
/* overlap with the SDIO interface for SD card
#define BOARD_SPI3A_NSS_PIN Port2Pin('A', 4)
#define BOARD_SPI3A_SCK_PIN Port2Pin('C',10)
#define BOARD_SPI3A_MISO_PIN Port2Pin('C',11)
#define BOARD_SPI3A_MOSI_PIN Port2Pin('C',12)
*/
#define BOARD_SDIO_D0 PC8 //Port2Pin('C', 8)
#define BOARD_SDIO_D1 PC9 //Port2Pin('C', 9)
#define BOARD_SDIO_D2 PC10 //Port2Pin('C',10)
#define BOARD_SDIO_D3 PC11 //Port2Pin('C',11)
#define BOARD_SDIO_CK PC12 //Port2Pin('C',12)
#define BOARD_SDIO_CMD PD2 //Port2Pin('D', 2)
#define BOARD_NR_GPIO_PINS 80
#define BOARD_NR_PWM_PINS 22
#define BOARD_NR_ADC_PINS 16
#define BOARD_NR_USED_PINS 22
#define BOARD_JTMS_SWDIO_PIN PA13 //Port2Pin('A',13)
#define BOARD_JTCK_SWCLK_PIN PA14 //Port2Pin('A',14)
#define BOARD_JTDI_PIN PA15 //Port2Pin('A',15)
#define BOARD_JTDO_PIN PB3 //Port2Pin('B', 3)
#define BOARD_NJTRST_PIN PB4 //Port2Pin('B', 4)
enum {
PA0,PA1,PA2,PA3,PA4,PA5,PA6,PA7,PA8,PA9,PA10,PA11,PA12,PA13,PA14,PA15,
PB0,PB1,PB2,PB3,PB4,PB5,PB6,PB7,PB8,PB9,PB10,PB11,PB12,PB13,PB14,PB15,
PC0,PC1,PC2,PC3,PC4,PC5,PC6,PC7,PC8,PC9,PC10,PC11,PC12,PC13,PC14,PC15,
PD0,PD1,PD2,PD3,PD4,PD5,PD6,PD7,PD8,PD9,PD10,PD11,PD12,PD13,PD14,PD15,
PE0,PE1,PE2,PE3,PE4,PE5,PE6,PE7,PE8,PE9,PE10,PE11,PE12,PE13,PE14,PE15,
#if 0
PF0,PF1,PF2,PF3,PF4,PF5,PF6,PF7,PF8,PF9,PF10,PF11,PF12,PF13,PF14,PF15,
PG0,PG1,PG2,PG3,PG4,PG5,PG6,PG7,PG8,PG9,PG10,PG11,PG12,PG13,PG14,PG15
#endif
};
#endif

View File

@ -0,0 +1,219 @@
/*
* Linker script for libmaple.
*
* Original author "lanchon" from ST forums, with modifications by LeafLabs.
*/
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/*
* Configure other libraries we want in the link.
*
* libgcc, libc, and libm are common across supported toolchains.
* However, some toolchains require additional archives which aren't
* present everywhere (e.g. ARM's gcc-arm-embedded releases).
*
* To hack around this, we let the build system specify additional
* archives by putting the right extra_libs.inc (in a directory under
* toolchains/) in our search path.
*/
GROUP(libgcc.a libc.a libm.a)
INCLUDE extra_libs.inc
/*
* These force the linker to search for vector table symbols.
*
* These symbols vary by STM32 family (and also within families).
* It's up to the build system to configure the link's search path
* properly for the target MCU.
*/
INCLUDE vector_symbols.inc
/* STM32 vector table. */
EXTERN(__stm32_vector_table)
/* C runtime initialization function. */
EXTERN(start_c)
/* main entry point */
EXTERN(main)
/* Initial stack pointer value. */
EXTERN(__msp_init)
PROVIDE(__msp_init = ORIGIN(ram) + LENGTH(ram));
/* Reset vector and chip reset entry point */
EXTERN(__start__)
ENTRY(__start__)
PROVIDE(__exc_reset = __start__);
/* Heap boundaries, for libmaple */
EXTERN(_lm_heap_start);
EXTERN(_lm_heap_end);
SECTIONS
{
.text :
{
__text_start__ = .;
/*
* STM32 vector table. Leave this here. Yes, really.
*/
*(.stm32.interrupt_vector)
/*
* Program code and vague linking
*/
*(.text .text.* .gnu.linkonce.t.*)
*(.plt)
*(.gnu.warning)
*(.glue_7t) *(.glue_7) *(.vfp11_veneer)
*(.ARM.extab* .gnu.linkonce.armextab.*)
*(.gcc_except_table)
*(.eh_frame_hdr)
*(.eh_frame)
. = ALIGN(4);
KEEP(*(.init))
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
. = ALIGN(0x4);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*crtend.o(.ctors))
. = ALIGN(4);
KEEP(*(.fini))
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*crtend.o(.dtors))
} > REGION_TEXT
/*
* End of text
*/
.text.align :
{
. = ALIGN(8);
__text_end__ = .;
} > REGION_TEXT
/*
* .ARM.exidx exception unwinding; mandated by ARM's C++ ABI
*/
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > REGION_RODATA
__exidx_end = .;
/*
* .data
*/
.data :
{
. = ALIGN(8);
__data_start__ = .;
*(.got.plt) *(.got)
*(.data .data.* .gnu.linkonce.d.*)
. = ALIGN(8);
__data_end__ = .;
} > REGION_DATA AT> REGION_RODATA
/*
* Read-only data
*/
.rodata :
{
*(.rodata .rodata.* .gnu.linkonce.r.*)
/* .USER_FLASH: We allow users to allocate into Flash here */
*(.USER_FLASH)
/* ROM image configuration; for C startup */
. = ALIGN(4);
_lm_rom_img_cfgp = .;
LONG(LOADADDR(.data));
/*
* Heap: Linker scripts may choose a custom heap by overriding
* _lm_heap_start and _lm_heap_end. Otherwise, the heap is in
* internal SRAM, beginning after .bss, and growing towards
* the stack.
*
* I'm shoving these here naively; there's probably a cleaner way
* to go about this. [mbolivar]
*/
_lm_heap_start = DEFINED(_lm_heap_start) ? _lm_heap_start : _end;
_lm_heap_end = DEFINED(_lm_heap_end) ? _lm_heap_end : __msp_init;
} > REGION_RODATA
/*
* .bss
*/
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
*(.bss .bss.* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN (8);
__bss_end__ = .;
_end = __bss_end__;
} > REGION_BSS
/*
* Debugging sections
*/
.stab 0 (NOLOAD) : { *(.stab) }
.stabstr 0 (NOLOAD) : { *(.stabstr) }
/* DWARF debug sections.
* Symbols in the DWARF debugging sections are relative to the beginning
* of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
.note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
.ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
/DISCARD/ : { *(.note.GNU-stack) }
}

View File

@ -0,0 +1,7 @@
/*
* Extra archives needed by ARM's GCC ARM Embedded arm-none-eabi-
* releases (https://launchpad.net/gcc-arm-embedded/).
*/
/* This is for the provided newlib. */
GROUP(libnosys.a)

View File

@ -0,0 +1,20 @@
/*
* Discovery F4 (STM32F407VGT6, high density) linker script for
* Flash builds.
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 125K
rom (rx) : ORIGIN = 0x08010000, LENGTH = 960K /* ala42 */
}
/* GROUP(libcs4_stm32_high_density.a) */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
_FLASH_BUILD = 1;
INCLUDE common.inc

View File

@ -0,0 +1,20 @@
/*
* STM32F4xx high density linker script for
* JTAG (bare metal, no bootloader) builds.
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
}
/* GROUP(libcs3_stm32_high_density.a) */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
_FLASH_BUILD = 1;
INCLUDE common.inc

View File

@ -0,0 +1,78 @@
EXTERN(__cs3_stack)
EXTERN(__cs3_reset)
EXTERN(__exc_nmi)
EXTERN(__exc_hardfault)
EXTERN(__exc_memmanage)
EXTERN(__exc_busfault)
EXTERN(__exc_usagefault)
EXTERN(__stm32reservedexception7)
EXTERN(__stm32reservedexception8)
EXTERN(__stm32reservedexception9)
EXTERN(__stm32reservedexception10)
EXTERN(__exc_svc)
EXTERN(__exc_debug_monitor)
EXTERN(__stm32reservedexception13)
EXTERN(__exc_pendsv)
EXTERN(__exc_systick)
EXTERN(__irq_wwdg)
EXTERN(__irq_pvd)
EXTERN(__irq_tamper)
EXTERN(__irq_rtc)
EXTERN(__irq_flash)
EXTERN(__irq_rcc)
EXTERN(__irq_exti0)
EXTERN(__irq_exti1)
EXTERN(__irq_exti2)
EXTERN(__irq_exti3)
EXTERN(__irq_exti4)
EXTERN(__irq_dma1_channel1)
EXTERN(__irq_dma1_channel2)
EXTERN(__irq_dma1_channel3)
EXTERN(__irq_dma1_channel4)
EXTERN(__irq_dma1_channel5)
EXTERN(__irq_dma1_channel6)
EXTERN(__irq_dma1_channel7)
EXTERN(__irq_adc)
EXTERN(__irq_usb_hp_can_tx)
EXTERN(__irq_usb_lp_can_rx0)
EXTERN(__irq_can_rx1)
EXTERN(__irq_can_sce)
EXTERN(__irq_exti9_5)
EXTERN(__irq_tim1_brk)
EXTERN(__irq_tim1_up)
EXTERN(__irq_tim1_trg_com)
EXTERN(__irq_tim1_cc)
EXTERN(__irq_tim2)
EXTERN(__irq_tim3)
EXTERN(__irq_tim4)
EXTERN(__irq_i2c1_ev)
EXTERN(__irq_i2c1_er)
EXTERN(__irq_i2c2_ev)
EXTERN(__irq_i2c2_er)
EXTERN(__irq_spi1)
EXTERN(__irq_spi2)
EXTERN(__irq_usart1)
EXTERN(__irq_usart2)
EXTERN(__irq_usart3)
EXTERN(__irq_exti15_10)
EXTERN(__irq_rtcalarm)
EXTERN(__irq_usbwakeup)
EXTERN(__irq_tim8_brk)
EXTERN(__irq_tim8_up)
EXTERN(__irq_tim8_trg_com)
EXTERN(__irq_tim8_cc)
EXTERN(__irq_adc3)
EXTERN(__irq_fsmc)
EXTERN(__irq_sdio)
EXTERN(__irq_tim5)
EXTERN(__irq_spi3)
EXTERN(__irq_uart4)
EXTERN(__irq_uart5)
EXTERN(__irq_tim6)
EXTERN(__irq_tim7)
EXTERN(__irq_dma2_channel1)
EXTERN(__irq_dma2_channel2)
EXTERN(__irq_dma2_channel3)
EXTERN(__irq_dma2_channel4_5)

View File

@ -0,0 +1,19 @@
/*
* aeroquad32 (STM32F103VET6, high density) linker script for
* RAM builds.
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 61K
rom (rx) : ORIGIN = 0x08010000, LENGTH = 0K /* ala42 */
}
GROUP(libcs3_stm32_high_density.a)
REGION_ALIAS("REGION_TEXT", ram);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", ram);
INCLUDE common.inc

View File

@ -0,0 +1,78 @@
EXTERN(__msp_init)
EXTERN(__exc_reset)
EXTERN(__exc_nmi)
EXTERN(__exc_hardfault)
EXTERN(__exc_memmanage)
EXTERN(__exc_busfault)
EXTERN(__exc_usagefault)
EXTERN(__stm32reservedexception7)
EXTERN(__stm32reservedexception8)
EXTERN(__stm32reservedexception9)
EXTERN(__stm32reservedexception10)
EXTERN(__exc_svc)
EXTERN(__exc_debug_monitor)
EXTERN(__stm32reservedexception13)
EXTERN(__exc_pendsv)
EXTERN(__exc_systick)
EXTERN(__irq_wwdg)
EXTERN(__irq_pvd)
EXTERN(__irq_tamper)
EXTERN(__irq_rtc)
EXTERN(__irq_flash)
EXTERN(__irq_rcc)
EXTERN(__irq_exti0)
EXTERN(__irq_exti1)
EXTERN(__irq_exti2)
EXTERN(__irq_exti3)
EXTERN(__irq_exti4)
EXTERN(__irq_dma1_channel1)
EXTERN(__irq_dma1_channel2)
EXTERN(__irq_dma1_channel3)
EXTERN(__irq_dma1_channel4)
EXTERN(__irq_dma1_channel5)
EXTERN(__irq_dma1_channel6)
EXTERN(__irq_dma1_channel7)
EXTERN(__irq_adc)
EXTERN(__irq_usb_hp_can_tx)
EXTERN(__irq_usb_lp_can_rx0)
EXTERN(__irq_can_rx1)
EXTERN(__irq_can_sce)
EXTERN(__irq_exti9_5)
EXTERN(__irq_tim1_brk)
EXTERN(__irq_tim1_up)
EXTERN(__irq_tim1_trg_com)
EXTERN(__irq_tim1_cc)
EXTERN(__irq_tim2)
EXTERN(__irq_tim3)
EXTERN(__irq_tim4)
EXTERN(__irq_i2c1_ev)
EXTERN(__irq_i2c1_er)
EXTERN(__irq_i2c2_ev)
EXTERN(__irq_i2c2_er)
EXTERN(__irq_spi1)
EXTERN(__irq_spi2)
EXTERN(__irq_usart1)
EXTERN(__irq_usart2)
EXTERN(__irq_usart3)
EXTERN(__irq_exti15_10)
EXTERN(__irq_rtcalarm)
EXTERN(__irq_usbwakeup)
EXTERN(__irq_tim8_brk)
EXTERN(__irq_tim8_up)
EXTERN(__irq_tim8_trg_com)
EXTERN(__irq_tim8_cc)
EXTERN(__irq_adc3)
EXTERN(__irq_fsmc)
EXTERN(__irq_sdio)
EXTERN(__irq_tim5)
EXTERN(__irq_spi3)
EXTERN(__irq_uart4)
EXTERN(__irq_uart5)
EXTERN(__irq_tim6)
EXTERN(__irq_tim7)
EXTERN(__irq_dma2_channel1)
EXTERN(__irq_dma2_channel2)
EXTERN(__irq_dma2_channel3)
EXTERN(__irq_dma2_channel4_5)

View File

@ -0,0 +1,6 @@
// API compatibility
#include "variant.h"

View File

@ -0,0 +1,323 @@
/* STM32 ISR weak declarations */
.thumb
/* Default handler for all non-overridden interrupts and exceptions */
.globl __default_handler
.type __default_handler, %function
__default_handler:
b .
.weak __exc_nmi
.globl __exc_nmi
.set __exc_nmi, __default_handler
.weak __exc_hardfault
.globl __exc_hardfault
.set __exc_hardfault, __default_handler
.weak __exc_memmanage
.globl __exc_memmanage
.set __exc_memmanage, __default_handler
.weak __exc_busfault
.globl __exc_busfault
.set __exc_busfault, __default_handler
.weak __exc_usagefault
.globl __exc_usagefault
.set __exc_usagefault, __default_handler
.weak __stm32reservedexception7
.globl __stm32reservedexception7
.set __stm32reservedexception7, __default_handler
.weak __stm32reservedexception8
.globl __stm32reservedexception8
.set __stm32reservedexception8, __default_handler
.weak __stm32reservedexception9
.globl __stm32reservedexception9
.set __stm32reservedexception9, __default_handler
.weak __stm32reservedexception10
.globl __stm32reservedexception10
.set __stm32reservedexception10, __default_handler
.weak __exc_svc
.globl __exc_svc
.set __exc_svc, __default_handler
.weak __exc_debug_monitor
.globl __exc_debug_monitor
.set __exc_debug_monitor, __default_handler
.weak __stm32reservedexception13
.globl __stm32reservedexception13
.set __stm32reservedexception13, __default_handler
.weak __exc_pendsv
.globl __exc_pendsv
.set __exc_pendsv, __default_handler
.weak __exc_systick
.globl __exc_systick
.set __exc_systick, __default_handler
.weak __irq_wwdg
.globl __irq_wwdg
.set __irq_wwdg, __default_handler
.weak __irq_pvd
.globl __irq_pvd
.set __irq_pvd, __default_handler
.weak __irq_tamper
.globl __irq_tamper
.set __irq_tamper, __default_handler
.weak __irq_rtc
.globl __irq_rtc
.set __irq_rtc, __default_handler
.weak __irq_flash
.globl __irq_flash
.set __irq_flash, __default_handler
.weak __irq_rcc
.globl __irq_rcc
.set __irq_rcc, __default_handler
.weak __irq_exti0
.globl __irq_exti0
.set __irq_exti0, __default_handler
.weak __irq_exti1
.globl __irq_exti1
.set __irq_exti1, __default_handler
.weak __irq_exti2
.globl __irq_exti2
.set __irq_exti2, __default_handler
.weak __irq_exti3
.globl __irq_exti3
.set __irq_exti3, __default_handler
.weak __irq_exti4
.globl __irq_exti4
.set __irq_exti4, __default_handler
.weak __irq_dma1_channel1
.globl __irq_dma1_channel1
.set __irq_dma1_channel1, __default_handler
.weak __irq_dma1_channel2
.globl __irq_dma1_channel2
.set __irq_dma1_channel2, __default_handler
.weak __irq_dma1_channel3
.globl __irq_dma1_channel3
.set __irq_dma1_channel3, __default_handler
.weak __irq_dma1_channel4
.globl __irq_dma1_channel4
.set __irq_dma1_channel4, __default_handler
.weak __irq_dma1_channel5
.globl __irq_dma1_channel5
.set __irq_dma1_channel5, __default_handler
.weak __irq_dma1_channel6
.globl __irq_dma1_channel6
.set __irq_dma1_channel6, __default_handler
.weak __irq_dma1_channel7
.globl __irq_dma1_channel7
.set __irq_dma1_channel7, __default_handler
.weak __irq_adc
.globl __irq_adc
.set __irq_adc, __default_handler
.weak __irq_usb_hp_can_tx
.globl __irq_usb_hp_can_tx
.set __irq_usb_hp_can_tx, __default_handler
.weak __irq_usb_lp_can_rx0
.globl __irq_usb_lp_can_rx0
.set __irq_usb_lp_can_rx0, __default_handler
.weak __irq_can_rx1
.globl __irq_can_rx1
.set __irq_can_rx1, __default_handler
.weak __irq_can_sce
.globl __irq_can_sce
.set __irq_can_sce, __default_handler
.weak __irq_exti9_5
.globl __irq_exti9_5
.set __irq_exti9_5, __default_handler
.weak __irq_tim1_brk
.globl __irq_tim1_brk
.set __irq_tim1_brk, __default_handler
.weak __irq_tim1_up
.globl __irq_tim1_up
.set __irq_tim1_up, __default_handler
.weak __irq_tim1_trg_com
.globl __irq_tim1_trg_com
.set __irq_tim1_trg_com, __default_handler
.weak __irq_tim1_cc
.globl __irq_tim1_cc
.set __irq_tim1_cc, __default_handler
.weak __irq_tim2
.globl __irq_tim2
.set __irq_tim2, __default_handler
.weak __irq_tim3
.globl __irq_tim3
.set __irq_tim3, __default_handler
.weak __irq_tim4
.globl __irq_tim4
.set __irq_tim4, __default_handler
.weak __irq_i2c1_ev
.globl __irq_i2c1_ev
.set __irq_i2c1_ev, __default_handler
.weak __irq_i2c1_er
.globl __irq_i2c1_er
.set __irq_i2c1_er, __default_handler
.weak __irq_i2c2_ev
.globl __irq_i2c2_ev
.set __irq_i2c2_ev, __default_handler
.weak __irq_i2c2_er
.globl __irq_i2c2_er
.set __irq_i2c2_er, __default_handler
.weak __irq_spi1
.globl __irq_spi1
.set __irq_spi1, __default_handler
.weak __irq_spi2
.globl __irq_spi2
.set __irq_spi2, __default_handler
.weak __irq_usart1
.globl __irq_usart1
.set __irq_usart1, __default_handler
.weak __irq_usart2
.globl __irq_usart2
.set __irq_usart2, __default_handler
.weak __irq_usart3
.globl __irq_usart3
.set __irq_usart3, __default_handler
.weak __irq_exti15_10
.globl __irq_exti15_10
.set __irq_exti15_10, __default_handler
.weak __irq_rtcalarm
.globl __irq_rtcalarm
.set __irq_rtcalarm, __default_handler
.weak __irq_usbwakeup
.globl __irq_usbwakeup
.set __irq_usbwakeup, __default_handler
#if defined (STM32_HIGH_DENSITY)
.weak __irq_tim8_brk
.globl __irq_tim8_brk
.set __irq_tim8_brk, __default_handler
.weak __irq_tim8_up
.globl __irq_tim8_up
.set __irq_tim8_up, __default_handler
.weak __irq_tim8_trg_com
.globl __irq_tim8_trg_com
.set __irq_tim8_trg_com, __default_handler
.weak __irq_tim8_cc
.globl __irq_tim8_cc
.set __irq_tim8_cc, __default_handler
.weak __irq_adc3
.globl __irq_adc3
.set __irq_adc3, __default_handler
.weak __irq_fsmc
.globl __irq_fsmc
.set __irq_fsmc, __default_handler
.weak __irq_sdio
.globl __irq_sdio
.set __irq_sdio, __default_handler
.weak __irq_tim5
.globl __irq_tim5
.set __irq_tim5, __default_handler
.weak __irq_spi3
.globl __irq_spi3
.set __irq_spi3, __default_handler
.weak __irq_uart4
.globl __irq_uart4
.set __irq_uart4, __default_handler
.weak __irq_uart5
.globl __irq_uart5
.set __irq_uart5, __default_handler
.weak __irq_tim6
.globl __irq_tim6
.set __irq_tim6, __default_handler
.weak __irq_tim7
.globl __irq_tim7
.set __irq_tim7, __default_handler
.weak __irq_dma2_channel1
.globl __irq_dma2_channel1
.set __irq_dma2_channel1, __default_handler
.weak __irq_dma2_channel2
.globl __irq_dma2_channel2
.set __irq_dma2_channel2, __default_handler
.weak __irq_dma2_channel3
.globl __irq_dma2_channel3
.set __irq_dma2_channel3, __default_handler
.weak __irq_dma2_channel4_5
.globl __irq_dma2_channel4_5
.set __irq_dma2_channel4_5, __default_handler
#endif /* STM32_HIGH_DENSITY */
.weak __irq_DMA2_Stream4_IRQHandler
.globl __irq_DMA2_Stream4_IRQHandler
.set __irq_DMA2_Stream4_IRQHandler, __default_handler
.weak __irq_ETH_IRQHandler
.globl __irq_ETH_IRQHandler
.set __irq_ETH_IRQHandler, __default_handler
.weak __irq_ETH_WKUP_IRQHandler
.globl __irq_ETH_WKUP_IRQHandler
.set __irq_ETH_WKUP_IRQHandler, __default_handler
.weak __irq_CAN2_TX_IRQHandler
.globl __irq_CAN2_TX_IRQHandler
.set __irq_CAN2_TX_IRQHandler, __default_handler
.weak __irq_CAN2_RX0_IRQHandler
.globl __irq_CAN2_RX0_IRQHandler
.set __irq_CAN2_RX0_IRQHandler, __default_handler
.weak __irq_CAN2_RX1_IRQHandler
.globl __irq_CAN2_RX1_IRQHandler
.set __irq_CAN2_RX1_IRQHandler, __default_handler
.weak __irq_CAN2_SCE_IRQHandler
.globl __irq_CAN2_SCE_IRQHandler
.set __irq_CAN2_SCE_IRQHandler, __default_handler
.weak __irq_OTG_FS_IRQHandler
.globl __irq_OTG_FS_IRQHandler
.set __irq_OTG_FS_IRQHandler, __default_handler
.weak __irq_DMA2_Stream5_IRQHandler
.globl __irq_DMA2_Stream5_IRQHandler
.set __irq_DMA2_Stream5_IRQHandler, __default_handler
.weak __irq_DMA2_Stream6_IRQHandler
.globl __irq_DMA2_Stream6_IRQHandler
.set __irq_DMA2_Stream6_IRQHandler, __default_handler
.weak __irq_DMA2_Stream7_IRQHandler
.globl __irq_DMA2_Stream7_IRQHandler
.set __irq_DMA2_Stream7_IRQHandler, __default_handler
.weak __irq_USART6_IRQHandler
.globl __irq_USART6_IRQHandler
.set __irq_USART6_IRQHandler, __default_handler
.weak __irq_I2C3_EV_IRQHandler
.globl __irq_I2C3_EV_IRQHandler
.set __irq_I2C3_EV_IRQHandler, __default_handler
.weak __irq_I2C3_ER_IRQHandler
.globl __irq_I2C3_ER_IRQHandler
.set __irq_I2C3_ER_IRQHandler, __default_handler
.weak __irq_OTG_HS_EP1_OUT_IRQHandler
.globl __irq_OTG_HS_EP1_OUT_IRQHandler
.set __irq_OTG_HS_EP1_OUT_IRQHandler, __default_handler
.weak __irq_OTG_HS_EP1_IN_IRQHandler
.globl __irq_OTG_HS_EP1_IN_IRQHandler
.set __irq_OTG_HS_EP1_IN_IRQHandler, __default_handler
.weak __irq_OTG_HS_WKUP_IRQHandler
.globl __irq_OTG_HS_WKUP_IRQHandler
.set __irq_OTG_HS_WKUP_IRQHandler, __default_handler
.weak __irq_OTG_HS_IRQHandler
.globl __irq_OTG_HS_IRQHandler
.set __irq_OTG_HS_IRQHandler, __default_handler
.weak __irq_DCMI_IRQHandler
.globl __irq_DCMI_IRQHandler
.set __irq_DCMI_IRQHandler, __default_handler
.weak __irq_CRYP_IRQHandler
.globl __irq_CRYP_IRQHandler
.set __irq_CRYP_IRQHandler, __default_handler
.weak __irq_HASH_RNG_IRQHandler
.globl __irq_HASH_RNG_IRQHandler
.set __irq_HASH_RNG_IRQHandler, __default_handler
.weak __irq_FPU_IRQHandler
.globl __irq_FPU_IRQHandler
.set __irq_FPU_IRQHandler, __default_handler

View File

@ -0,0 +1,113 @@
/* STM32 vector table */
.section ".stm32.interrupt_vector"
.globl __stm32_vector_table
.type __stm32_vector_table, %object
__stm32_vector_table:
/* CM3 core interrupts */
.long __msp_init
.long __exc_reset
.long __exc_nmi
.long __exc_hardfault
.long __exc_memmanage
.long __exc_busfault
.long __exc_usagefault
.long __stm32reservedexception7
.long __stm32reservedexception8
.long __stm32reservedexception9
.long __stm32reservedexception10
.long __exc_svc
.long __exc_debug_monitor
.long __stm32reservedexception13
.long __exc_pendsv
.long __exc_systick
/* Peripheral interrupts */
.long __irq_wwdg
.long __irq_pvd
.long __irq_tamper
.long __irq_rtc
.long __irq_flash
.long __irq_rcc
.long __irq_exti0
.long __irq_exti1
.long __irq_exti2
.long __irq_exti3
.long __irq_exti4
.long __irq_dma1_channel1
.long __irq_dma1_channel2
.long __irq_dma1_channel3
.long __irq_dma1_channel4
.long __irq_dma1_channel5
.long __irq_dma1_channel6
.long __irq_dma1_channel7
.long __irq_adc
.long __irq_usb_hp_can_tx
.long __irq_usb_lp_can_rx0
.long __irq_can_rx1
.long __irq_can_sce
.long __irq_exti9_5
.long __irq_tim1_brk
.long __irq_tim1_up
.long __irq_tim1_trg_com
.long __irq_tim1_cc
.long __irq_tim2
.long __irq_tim3
.long __irq_tim4
.long __irq_i2c1_ev
.long __irq_i2c1_er
.long __irq_i2c2_ev
.long __irq_i2c2_er
.long __irq_spi1
.long __irq_spi2
.long __irq_usart1
.long __irq_usart2
.long __irq_usart3
.long __irq_exti15_10
.long __irq_rtcalarm
.long __irq_usbwakeup
#if defined (STM32_HIGH_DENSITY)
.long __irq_tim8_brk
.long __irq_tim8_up
.long __irq_tim8_trg_com
.long __irq_tim8_cc
.long __irq_adc3
.long __irq_fsmc
.long __irq_sdio
.long __irq_tim5
.long __irq_spi3
.long __irq_uart4
.long __irq_uart5
.long __irq_tim6
.long __irq_tim7
.long __irq_dma2_channel1
.long __irq_dma2_channel2
.long __irq_dma2_channel3
.long __irq_dma2_channel4_5
#endif /* STM32_HIGH_DENSITY */
.long __irq_DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */
.long __irq_ETH_IRQHandler /* Ethernet */
.long __irq_ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */
.long __irq_CAN2_TX_IRQHandler /* CAN2 TX */
.long __irq_CAN2_RX0_IRQHandler /* CAN2 RX0 */
.long __irq_CAN2_RX1_IRQHandler /* CAN2 RX1 */
.long __irq_CAN2_SCE_IRQHandler /* CAN2 SCE */
.long __irq_OTG_FS_IRQHandler /* USB OTG FS */
.long __irq_DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */
.long __irq_DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */
.long __irq_DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */
.long __irq_USART6_IRQHandler /* USART6 */
.long __irq_I2C3_EV_IRQHandler /* I2C3 event */
.long __irq_I2C3_ER_IRQHandler /* I2C3 error */
.long __irq_OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */
.long __irq_OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */
.long __irq_OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */
.long __irq_OTG_HS_IRQHandler /* USB OTG HS */
.long __irq_DCMI_IRQHandler /* DCMI */
.long __irq_CRYP_IRQHandler /* CRYP crypto */
.long __irq_HASH_RNG_IRQHandler /* Hash and Rng */
.long __irq_FPU_IRQHandler /* FPU */
.size __stm32_vector_table, . - __stm32_vector_table

View File

@ -0,0 +1,21 @@
#ifndef _VARIANT_ARDUINO_STM32_
#define _VARIANT_ARDUINO_STM32_
#define digitalPinToPort(P) ( PIN_MAP[P].gpio_device )
#define digitalPinToBitMask(P) ( BIT(PIN_MAP[P].gpio_bit) )
#define portOutputRegister(port) ( &(port->regs->ODR) )
#define portInputRegister(port) ( &(port->regs->IDR) )
#define portSetRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BSRR) )
#define portClearRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BRR) )
#define portConfigRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->CRL) )
static const uint8_t SS = BOARD_SPI1_NSS_PIN;
static const uint8_t SS1 = BOARD_SPI2_NSS_PIN;
static const uint8_t MOSI = BOARD_SPI1_MOSI_PIN;
static const uint8_t MISO = BOARD_SPI1_MISO_PIN;
static const uint8_t SCK = BOARD_SPI1_SCK_PIN;
#endif /* _VARIANT_ARDUINO_STM32_ */

View File

@ -0,0 +1,57 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
.text
.code 16
.thumb_func
.globl __start__
.type __start__, %function
__start__:
.fnstart
ldr r1,=__msp_init
mov sp,r1
ldr r1,=start_c
bx r1
.pool
.cantunwind
.fnend

View File

@ -0,0 +1,95 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2011 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* Copyright (c) 2006, 2007 CodeSourcery Inc
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
#include <stddef.h>
extern void __libc_init_array(void);
extern int main(int, char**, char**);
extern void exit(int) __attribute__((noreturn, weak));
/* The linker must ensure that these are at least 4-byte aligned. */
extern char __data_start__, __data_end__;
extern char __bss_start__, __bss_end__;
struct rom_img_cfg {
int *img_start;
};
extern char _lm_rom_img_cfgp;
void __attribute__((noreturn)) start_c(void) {
struct rom_img_cfg *img_cfg = (struct rom_img_cfg*)&_lm_rom_img_cfgp;
int *src = img_cfg->img_start;
int *dst = (int*)&__data_start__;
int exit_code;
/* Initialize .data, if necessary. */
if (src != dst) {
int *end = (int*)&__data_end__;
while (dst < end) {
*dst++ = *src++;
}
}
/* Zero .bss. */
dst = (int*)&__bss_start__;
while (dst < (int*)&__bss_end__) {
*dst++ = 0;
}
/* Run initializers. */
__libc_init_array();
/* Jump to main. */
exit_code = main(0, 0, 0);
if (exit) {
exit(exit_code);
}
/* If exit is NULL, make sure we don't return. */
for (;;)
continue;
}