diff --git a/boards.txt b/boards.txt index 9ce9fc22b8..dccd3aab82 100644 --- a/boards.txt +++ b/boards.txt @@ -86,6 +86,20 @@ Nucleo_64.menu.board_part_num.NUCLEO_F091RC.build.product_line=STM32F091xC Nucleo_64.menu.board_part_num.NUCLEO_F091RC.build.variant=NUCLEO_F091RC Nucleo_64.menu.board_part_num.NUCLEO_F091RC.build.cmsis_lib_gcc=arm_cortexM0l_math +# NUCLEO_F103RB board +# Support: Serial1 (USART1 on PA10, PA9) and Serial2 (USART3 on PC11, PC10) +Nucleo_64.menu.board_part_num.NUCLEO_F103RB=Nucleo F103RB +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.node="NODE_F103RB,NUCLEO" +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.upload.maximum_size=131072 +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.upload.maximum_data_size=20480 +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.mcu=cortex-m3 +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.f_cpu=72000000L +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.board=NUCLEO_F103RB +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.series=STM32F1xx +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.product_line=STM32F103xB +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.variant=NUCLEO_F103RB +Nucleo_64.menu.board_part_num.NUCLEO_F103RB.build.cmsis_lib_gcc=arm_cortexM3l_math + # NUCLEO_F303RE board # Support: Serial1 (USART1 on PA10, PA9) and Serial2 (USART2 on PA1, PA0) Nucleo_64.menu.board_part_num.NUCLEO_F303RE=Nucleo F303RE diff --git a/cores/arduino/WInterrupts.c b/cores/arduino/WInterrupts.c index 1a24ababde..bab81f2a80 100644 --- a/cores/arduino/WInterrupts.c +++ b/cores/arduino/WInterrupts.c @@ -22,6 +22,8 @@ extern "C" { #endif +#include "PinAF_STM32F1.h" + void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode) { uint32_t it_mode; @@ -46,6 +48,11 @@ void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode) it_mode = GPIO_MODE_IT_RISING; break; } + +#ifdef STM32F1xx + pinF1_DisconnectDebug(p); +#endif /* STM32F1xx */ + stm32_interrupt_enable(port, STM_GPIO_PIN(p), callback, it_mode); } diff --git a/cores/arduino/stm32/PinAF_STM32F1.h b/cores/arduino/stm32/PinAF_STM32F1.h new file mode 100644 index 0000000000..28d788de1d --- /dev/null +++ b/cores/arduino/stm32/PinAF_STM32F1.h @@ -0,0 +1,125 @@ +/* + ******************************************************************************* + * Copyright (c) 2017, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + */ + +#ifndef _PINAF_STM32F1_H +#define _PINAF_STM32F1_H + +#ifdef STM32F1xx + +#include "Arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +static inline void pinF1_DisconnectDebug(PinName pin) +{ + /** Enable this flag gives the possibility to use debug pins without any risk + * to lose traces + */ +#ifndef STM32F1_LOCK_DEBUG + // Enable AFIO clock + __HAL_RCC_AFIO_CLK_ENABLE(); + + // Disconnect JTAG-DP + SW-DP signals. + // Warning: Need to reconnect under reset + if ((pin == PA13) || (pin == PA14)) { + __HAL_AFIO_REMAP_SWJ_DISABLE(); // JTAG-DP Disabled and SW-DP Disabled + } + if ((pin == PA15) || (pin == PB3) || (pin == PB4)) { + __HAL_AFIO_REMAP_SWJ_NOJTAG(); // JTAG-DP Disabled and SW-DP enabled + } +#endif /* STM32F1_FORCE_DEBUG */ +} + +static inline void pin_SetF1AFPin(uint32_t afnum) +{ + // Enable AFIO clock + __HAL_RCC_AFIO_CLK_ENABLE(); + + if (afnum > 0) { + switch (afnum) { + case 1: // Remap SPI1 + __HAL_AFIO_REMAP_SPI1_ENABLE(); + break; + case 2: // Remap I2C1 + __HAL_AFIO_REMAP_I2C1_ENABLE(); + break; + case 3: // Remap USART1 + __HAL_AFIO_REMAP_USART1_ENABLE(); + break; + case 4: // Remap USART2 + __HAL_AFIO_REMAP_USART2_ENABLE(); + break; + case 5: // Partial Remap USART3 + __HAL_AFIO_REMAP_USART3_PARTIAL(); + break; + case 6: // Partial Remap TIM1 + __HAL_AFIO_REMAP_TIM1_PARTIAL(); + break; + case 7: // Partial Remap TIM3 + __HAL_AFIO_REMAP_TIM3_PARTIAL(); + break; + case 8: // Full Remap TIM2 + __HAL_AFIO_REMAP_TIM2_ENABLE(); + break; + case 9: // Full Remap TIM3 + __HAL_AFIO_REMAP_TIM3_ENABLE(); + break; +#if defined(AFIO_MAPR_CAN_REMAP_REMAP1) + case 10: // CAN_RX mapped to PB8, CAN_TX mapped to PB9 + __HAL_AFIO_REMAP_CAN1_2(); + break; + case 11: // CAN_RX mapped to PB8, CAN_TX mapped to PB9 + __HAL_AFIO_REMAP_CAN1_3(); + break; +#endif + case 12: // Full Remap USART3 + __HAL_AFIO_REMAP_USART3_ENABLE(); + break; + case 13: // Full Remap TIM1 + __HAL_AFIO_REMAP_TIM1_ENABLE(); + break; + case 14: // Full Remap TIM4 + __HAL_AFIO_REMAP_TIM4_ENABLE(); + break; + default: + break; + } + } +} + +#ifdef __cplusplus +} +#endif + +#endif /* STM32F1xx */ + +#endif /* _PINAF_STM32F1_H */ diff --git a/cores/arduino/stm32/analog.c b/cores/arduino/stm32/analog.c index 909f051b08..3a0a8ea24e 100644 --- a/cores/arduino/stm32/analog.c +++ b/cores/arduino/stm32/analog.c @@ -50,6 +50,7 @@ #include "hw_config.h" #include "analog.h" #include "timer.h" +#include "PinAF_STM32F1.h" #ifdef __cplusplus extern "C" { @@ -83,6 +84,7 @@ #error "ADC SAMPLINGTIME could not be defined" #endif +#ifndef STM32F1xx #ifdef ADC_CLOCK_SYNC_PCLK_DIV2 #define ADC_CLOCK_DIV ADC_CLOCK_SYNC_PCLK_DIV2 #elif defined(ADC_CLOCK_ASYNC_DIV1) @@ -92,6 +94,7 @@ #else #error "ADC_CLOCK_DIV could not be defined" #endif +#endif /* STM32F1xx */ #ifndef ADC_REGULAR_RANK_1 #define ADC_REGULAR_RANK_1 1 @@ -432,7 +435,8 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef *hadc) #ifdef __HAL_RCC_ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE(); #endif -#ifdef __HAL_RCC_ADC_CONFIG +/* For STM32F1xx, ADC prescaler is confgured in SystemClock_Config (variant.cpp) */ +#if defined(__HAL_RCC_ADC_CONFIG) && !defined(STM32F1xx) /* ADC Periph interface clock configuration */ __HAL_RCC_ADC_CONFIG(RCC_ADCCLKSOURCE_SYSCLK); #endif @@ -557,16 +561,18 @@ uint16_t adc_read_value(PinName pin) if (AdcHandle.Instance == NP) return 0; +#ifndef STM32F1xx AdcHandle.Init.ClockPrescaler = ADC_CLOCK_DIV; /* Asynchronous clock mode, input ADC clock divided */ AdcHandle.Init.Resolution = ADC_RESOLUTION_12B; /* 12-bit resolution for converted data */ + AdcHandle.Init.EOCSelection = ADC_EOC_SINGLE_CONV; /* EOC flag picked-up to indicate conversion end */ + AdcHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; /* Parameter discarded because software trigger chosen */ + AdcHandle.Init.DMAContinuousRequests = DISABLE; /* DMA one-shot mode selected (not applied to this example) */ +#endif AdcHandle.Init.DataAlign = ADC_DATAALIGN_RIGHT; /* Right-alignment for converted data */ AdcHandle.Init.ScanConvMode = DISABLE; /* Sequencer disabled (ADC conversion on only 1 channel: channel set on rank 1) */ - AdcHandle.Init.EOCSelection = ADC_EOC_SINGLE_CONV; /* EOC flag picked-up to indicate conversion end */ AdcHandle.Init.ContinuousConvMode = DISABLE; /* Continuous mode disabled to have only 1 conversion at each conversion trig */ AdcHandle.Init.DiscontinuousConvMode = DISABLE; /* Parameter discarded because sequencer is disabled */ AdcHandle.Init.ExternalTrigConv = ADC_SOFTWARE_START; /* Software start to trig the 1st conversion manually, without external event */ - AdcHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; /* Parameter discarded because software trigger chosen */ - AdcHandle.Init.DMAContinuousRequests = DISABLE; /* DMA one-shot mode selected (not applied to this example) */ AdcHandle.State = HAL_ADC_STATE_RESET; #if defined (STM32F0xx) || defined (STM32L0xx) AdcHandle.Init.LowPowerAutoWait = DISABLE; /* Auto-delayed conversion feature disabled */ @@ -609,9 +615,9 @@ uint16_t adc_read_value(PinName pin) return 0; } -#if defined (STM32F0xx) || defined (STM32F3xx) || defined (STM32L4xx) +#if defined (STM32F0xx) || defined (STM32F1xx) || defined (STM32F3xx) || defined (STM32L4xx) /*##-2.1- Calibrate ADC then Start the conversion process ####################*/ -#if defined (STM32F0xx) +#if defined (STM32F0xx) || defined (STM32F1xx) if (HAL_ADCEx_Calibration_Start(&AdcHandle) != HAL_OK) #else if (HAL_ADCEx_Calibration_Start(&AdcHandle, ADC_SINGLE_ENDED) != HAL_OK) @@ -687,7 +693,11 @@ void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(function)); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(function); +#endif /* STM32F1xx */ GPIO_InitStruct.Pin = STM_GPIO_PIN(g_current_pin); HAL_GPIO_Init(port, &GPIO_InitStruct); diff --git a/cores/arduino/stm32/digital_io.c b/cores/arduino/stm32/digital_io.c index 3436121ac4..3824947999 100644 --- a/cores/arduino/stm32/digital_io.c +++ b/cores/arduino/stm32/digital_io.c @@ -38,6 +38,7 @@ #include "digital_io.h" #include "stm32_def.h" #include "hw_config.h" +#include "PinAF_STM32F1.h" #ifdef __cplusplus extern "C" { @@ -59,6 +60,9 @@ void digital_io_init(PinName pin, uint32_t mode, uint32_t pull) GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStructure.Mode = mode; GPIO_InitStructure.Pull = pull; +#ifdef STM32F1xx + pinF1_DisconnectDebug(pin); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStructure); } diff --git a/cores/arduino/stm32/interrupt.c b/cores/arduino/stm32/interrupt.c index 3bcc62039d..caa3ce5c48 100644 --- a/cores/arduino/stm32/interrupt.c +++ b/cores/arduino/stm32/interrupt.c @@ -170,8 +170,18 @@ uint8_t get_pin_id(uint16_t pin) void stm32_interrupt_enable(GPIO_TypeDef *port, uint16_t pin, void (*callback)(void), uint32_t mode) { GPIO_InitTypeDef GPIO_InitStruct; - uint32_t pull; uint8_t id = get_pin_id(pin); + +#ifdef STM32F1xx + uint8_t position; + uint32_t CRxRegOffset = 0; + uint32_t ODRRegOffset = 0; + volatile uint32_t *CRxRegister; + const uint32_t ConfigMask = 0x00000008; //MODE0 == 0x0 && CNF0 == 0x2 +#else + uint32_t pull; +#endif /* STM32F1xx */ + // GPIO pin configuration GPIO_InitStruct.Pin = pin; GPIO_InitStruct.Mode = mode; @@ -179,6 +189,7 @@ void stm32_interrupt_enable(GPIO_TypeDef *port, uint16_t pin, void (*callback)(v //read the pull mode directly in the register as no function exists to get it. //Do it in case the user already defines the IO through the digital io //interface +#ifndef STM32F1xx pull = port->PUPDR; #ifdef GPIO_PUPDR_PUPD0 pull &=(GPIO_PUPDR_PUPD0<<(id*2)); @@ -186,7 +197,28 @@ void stm32_interrupt_enable(GPIO_TypeDef *port, uint16_t pin, void (*callback)(v #else pull &=(GPIO_PUPDR_PUPDR0<<(id*2)); GPIO_InitStruct.Pull = (GPIO_PUPDR_PUPDR0 & (pull>>(id*2))); -#endif +#endif /* GPIO_PUPDR_PUPD0 */ +#else + CRxRegister = (pin < GPIO_PIN_8) ? &port->CRL : &port->CRH; + + for (position = 0; position < 16; position++) { + if(pin == (0x0001 << position)) { + CRxRegOffset = (pin < GPIO_PIN_8) ? (position << 2) : ((position - 8) << 2); + ODRRegOffset = position; + } + } + + if((*CRxRegister & ((GPIO_CRL_MODE0 | GPIO_CRL_CNF0) << CRxRegOffset)) == (ConfigMask << CRxRegOffset)) { + if((port->ODR & (GPIO_ODR_ODR0 << ODRRegOffset)) == (GPIO_ODR_ODR0 << ODRRegOffset)) { + GPIO_InitStruct.Pull = GPIO_PULLUP; + } else { + GPIO_InitStruct.Pull = GPIO_PULLDOWN; + } + } else { + GPIO_InitStruct.Pull = GPIO_NOPULL; + } +#endif /* STM32F1xx */ + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(port, &GPIO_InitStruct); diff --git a/cores/arduino/stm32/spi_com.c b/cores/arduino/stm32/spi_com.c index 8c2f8fd2dc..a1f0cc0e73 100644 --- a/cores/arduino/stm32/spi_com.c +++ b/cores/arduino/stm32/spi_com.c @@ -49,6 +49,7 @@ #include "stm32_def.h" #include "hw_config.h" #include "spi_com.h" +#include "PinAF_STM32F1.h" #ifdef __cplusplus extern "C" { @@ -275,7 +276,11 @@ void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb) GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->pin_mosi,PinMap_SPI_MOSI)); GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->pin_mosi,PinMap_SPI_MOSI)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_mosi,PinMap_SPI_MOSI))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_mosi,PinMap_SPI_MOSI)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); } @@ -285,7 +290,11 @@ void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb) GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->pin_miso,PinMap_SPI_MISO)); GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->pin_miso,PinMap_SPI_MISO)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_miso,PinMap_SPI_MISO))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_miso,PinMap_SPI_MISO)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); } @@ -303,7 +312,11 @@ void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb) GPIO_InitStruct.Pull = GPIO_PULLUP; } GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_sclk,PinMap_SPI_SCLK))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_sclk,PinMap_SPI_SCLK)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); } @@ -313,7 +326,11 @@ void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb) GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->pin_ssel,PinMap_SPI_SSEL)); GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->pin_ssel,PinMap_SPI_SSEL)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_ssel,PinMap_SPI_SSEL))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_ssel,PinMap_SPI_SSEL)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); } diff --git a/cores/arduino/stm32/stm32_def_build.h b/cores/arduino/stm32/stm32_def_build.h index a591946fee..798ae4cd00 100644 --- a/cores/arduino/stm32/stm32_def_build.h +++ b/cores/arduino/stm32/stm32_def_build.h @@ -40,6 +40,8 @@ #define CMSIS_STARTUP_FILE "startup_stm32l476xx.s" #elif defined(STM32L432xx) #define CMSIS_STARTUP_FILE "startup_stm32l432xx.s" +#elif defined(STM32F103xB) +#define CMSIS_STARTUP_FILE "startup_stm32f103xb.s" #else #error UNKNOWN CHIP #endif diff --git a/cores/arduino/stm32/stm32_eeprom.c b/cores/arduino/stm32/stm32_eeprom.c index 33bf66a6b9..0333d41f86 100644 --- a/cores/arduino/stm32/stm32_eeprom.c +++ b/cores/arduino/stm32/stm32_eeprom.c @@ -72,6 +72,9 @@ #ifdef STM32F0xx // Flash base address (Bank2, page 256) #define FLASH_BASE_ADDRESS 0x0803F800 +#elif defined (STM32F1xx) +#define FLASH_BASE_ADDRESS ((uint32_t)((FLASH_BANK1_END + 1) - FLASH_PAGE_SIZE)) //0x0801FC00 +#define FLASH_PAGE_NUMBER 127 #elif defined (STM32F3xx) #define FLASH_BASE_ADDRESS ((uint32_t)((0x0807FFFF + 1) - FLASH_PAGE_SIZE)) //0x0807F800 #elif defined (STM32F4xx) @@ -173,7 +176,8 @@ void set_data_to_flash(void) uint32_t offset = 0; uint32_t address = FLASH_BASE_ADDRESS; uint32_t address_end = FLASH_BASE_ADDRESS + E2END; -#if defined (STM32F0xx) || defined (STM32F3xx) || defined (STM32L0xx) || defined(STM32L4xx) +#if defined (STM32F0xx) || defined (STM32F1xx) || defined (STM32F3xx) || \ + defined (STM32L0xx) || defined(STM32L4xx) uint32_t pageError = 0; uint64_t data = 0; @@ -183,6 +187,9 @@ void set_data_to_flash(void) EraseInitStruct.Banks = FLASH_BANK_NUMBER; EraseInitStruct.Page = FLASH_PAGE_NUMBER; #else // STM32F4xx +#ifdef STM32F1xx + EraseInitStruct.Banks = FLASH_BANK_1; +#endif EraseInitStruct.PageAddress = FLASH_BASE_ADDRESS; #endif EraseInitStruct.NbPages = 1; diff --git a/cores/arduino/stm32/timer.h b/cores/arduino/stm32/timer.h index a64e5be94d..a73ea80383 100644 --- a/cores/arduino/stm32/timer.h +++ b/cores/arduino/stm32/timer.h @@ -127,17 +127,17 @@ struct timer_s{ #endif #endif #if defined(TIM15_BASE) && !defined(TIM15_IRQn) -#if defined(STM32F3xx) || defined(STM32L4xx) +#if defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L4xx) #define TIM15_IRQn TIM1_BRK_TIM15_IRQn #endif #endif #if defined(TIM16_BASE) && !defined(TIM16_IRQn) -#if defined(STM32F3xx) || defined(STM32L4xx) +#if defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L4xx) #define TIM16_IRQn TIM1_UP_TIM16_IRQn #endif #endif #if defined(TIM17_BASE) && !defined(TIM17_IRQn) -#if defined(STM32F3xx) || defined(STM32L4xx) +#if defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L4xx) #define TIM17_IRQn TIM1_TRG_COM_TIM17_IRQn #endif #endif diff --git a/cores/arduino/stm32/twi.c b/cores/arduino/stm32/twi.c index 1412729c76..4db35d0c18 100644 --- a/cores/arduino/stm32/twi.c +++ b/cores/arduino/stm32/twi.c @@ -47,10 +47,10 @@ /** @addtogroup STM32F4xx_System_Private_Includes * @{ */ - #include "stm32_def.h" #include "hw_config.h" #include "twi.h" +#include "PinAF_STM32F1.h" /** * @} @@ -168,6 +168,9 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u __HAL_RCC_I2C1_FORCE_RESET(); __HAL_RCC_I2C1_RELEASE_RESET(); obj->irq = I2C1_EV_IRQn; +#ifdef STM32F1xx + obj->irqER = I2C1_ER_IRQn; +#endif i2c_handles[0] = handle; } #endif @@ -181,6 +184,9 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u obj->irq = I2C2_IRQn; #else obj->irq = I2C2_EV_IRQn; +#ifdef STM32F1xx + obj->irqER = I2C2_ER_IRQn; +#endif #endif i2c_handles[1] = handle; } @@ -212,7 +218,11 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->scl,PinMap_I2C_SCL)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->scl,PinMap_I2C_SCL)); +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->scl,PinMap_I2C_SCL))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->scl,PinMap_I2C_SCL)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); //SDA @@ -221,7 +231,11 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->sda,PinMap_I2C_SDA)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->sda,PinMap_I2C_SDA)); +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->sda,PinMap_I2C_SDA))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->sda,PinMap_I2C_SDA)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); handle->Instance = obj->i2c; @@ -242,6 +256,10 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u if(master == 0) { HAL_NVIC_SetPriority(obj->irq, 0, 1); HAL_NVIC_EnableIRQ(obj->irq); +#ifdef STM32F1xx + HAL_NVIC_SetPriority(obj->irqER, 0, 1); + HAL_NVIC_EnableIRQ(obj->irqER); +#endif } // Init the I2C @@ -256,6 +274,9 @@ void i2c_custom_init(i2c_t *obj, i2c_timing_e timing, uint32_t addressingMode, u void i2c_deinit(i2c_t *obj) { HAL_NVIC_DisableIRQ(obj->irq); +#ifdef STM32F1xx + HAL_NVIC_DisableIRQ(obj->irqER); +#endif HAL_I2C_DeInit(&(obj->handle)); } @@ -402,8 +423,16 @@ i2c_t *get_i2c_obj(I2C_HandleTypeDef *hi2c){ */ void i2c_attachSlaveRxEvent(i2c_t *obj, void (*function)(uint8_t*, int) ) { + if((obj == NULL) || (function == NULL)) + return; + obj->i2c_onSlaveReceive = function; +#ifdef STM32F1xx + obj->i2cTxRxBufferSize = 0; + HAL_I2C_Slave_Receive_IT(&(obj->handle), obj->i2cTxRxBuffer, I2C_TXRX_BUFFER_SIZE); +#else HAL_I2C_EnableListen_IT(&(obj->handle)); +#endif } /** @brief sets function called before a slave write operation @@ -413,10 +442,64 @@ void i2c_attachSlaveRxEvent(i2c_t *obj, void (*function)(uint8_t*, int) ) */ void i2c_attachSlaveTxEvent(i2c_t *obj, void (*function)(void) ) { + if((obj == NULL) || (function == NULL)) + return; + obj->i2c_onSlaveTransmit = function; +#ifdef STM32F1xx + /* Fill i2c buffer with data to transmit otherwize the buffer will be empty + when master will read the data for the first time */ + obj->i2cTxRxBufferSize = 0; + obj->i2c_onSlaveTransmit(); + HAL_I2C_Slave_Transmit_IT(&(obj->handle), obj->i2cTxRxBuffer, obj->i2cTxRxBufferSize); +#else HAL_I2C_EnableListen_IT(&(obj->handle)); +#endif +} + +#ifdef STM32F1xx + +/** @brief Slave Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + i2c_t *obj = get_i2c_obj(hi2c); + + if(NULL != obj->i2c_onSlaveTransmit) { + // reset buffer size and fill buffer with new data before the next Tx + obj->i2cTxRxBufferSize = 0; + obj->i2c_onSlaveTransmit(); + HAL_I2C_Slave_Transmit_IT(hi2c, obj->i2cTxRxBuffer, obj->i2cTxRxBufferSize); + } +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + uint8_t nbData = 0; + i2c_t *obj = get_i2c_obj(hi2c); + + if(NULL != obj->i2c_onSlaveReceive) { + nbData = I2C_TXRX_BUFFER_SIZE - obj->handle.XferCount; + + if(nbData != 0) { + obj->i2c_onSlaveReceive(obj->i2cTxRxBuffer, nbData); + } + + HAL_I2C_Slave_Receive_IT(hi2c, obj->i2cTxRxBuffer, I2C_TXRX_BUFFER_SIZE); + } } +#else /* Others */ + /** * @brief Slave Address Match callback. * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains @@ -469,6 +552,8 @@ void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) HAL_I2C_EnableListen_IT(hi2c); } +#endif /* STM32F1xx */ + /** * @brief I2C error callback. * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains @@ -477,7 +562,11 @@ void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) */ void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) { +#ifdef STM32F1xx + UNUSED(hi2c); +#else HAL_I2C_EnableListen_IT(hi2c); +#endif } /** diff --git a/cores/arduino/stm32/twi.h b/cores/arduino/stm32/twi.h index 348a9921e8..bd865b9e45 100644 --- a/cores/arduino/stm32/twi.h +++ b/cores/arduino/stm32/twi.h @@ -67,6 +67,9 @@ struct i2c_s { PinName sda; PinName scl; IRQn_Type irq; +#ifdef STM32F1xx + IRQn_Type irqER; +#endif uint8_t slaveMode; void (*i2c_onSlaveReceive)(uint8_t *, int); void (*i2c_onSlaveTransmit)(void); diff --git a/cores/arduino/stm32/uart.c b/cores/arduino/stm32/uart.c index 03beb72094..24fa03acd1 100644 --- a/cores/arduino/stm32/uart.c +++ b/cores/arduino/stm32/uart.c @@ -51,6 +51,7 @@ #include "digital_io.h" #include "interrupt.h" #include "variant.h" +#include "PinAF_STM32F1.h" #ifdef __cplusplus extern "C" { @@ -215,7 +216,11 @@ void uart_init(serial_t *obj) GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->pin_rx,PinMap_UART_RX)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->pin_rx,PinMap_UART_RX)); +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_rx,PinMap_UART_RX))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_rx,PinMap_UART_RX)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); //TX @@ -224,7 +229,11 @@ void uart_init(serial_t *obj) GPIO_InitStruct.Mode = STM_PIN_MODE(pinmap_function(obj->pin_tx,PinMap_UART_TX)); GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Pull = STM_PIN_PUPD(pinmap_function(obj->pin_tx,PinMap_UART_TX)); +#ifdef STM32F1xx + pin_SetF1AFPin(STM_PIN_AFNUM(pinmap_function(obj->pin_tx,PinMap_UART_TX))); +#else GPIO_InitStruct.Alternate = STM_PIN_AFNUM(pinmap_function(obj->pin_tx,PinMap_UART_TX)); +#endif /* STM32F1xx */ HAL_GPIO_Init(port, &GPIO_InitStruct); //Configure uart @@ -519,7 +528,7 @@ void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) { void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) { volatile uint32_t tmpval; -#ifdef STM32F4xx +#if defined(STM32F1xx) || defined(STM32F4xx) if (__HAL_UART_GET_FLAG(huart, UART_FLAG_PE) != RESET) { tmpval = huart->Instance->DR; // Clear PE flag } else if (__HAL_UART_GET_FLAG(huart, UART_FLAG_FE) != RESET) { @@ -659,4 +668,5 @@ void UART8_IRQHandler(void) } #endif + /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/libraries/Wire/Wire.cpp b/libraries/Wire/Wire.cpp index e14f1b6d33..48f5c9dece 100644 --- a/libraries/Wire/Wire.cpp +++ b/libraries/Wire/Wire.cpp @@ -81,6 +81,7 @@ void TwoWire::begin(uint8_t address) i2c_custom_init(&_i2c,I2C_100KHz,I2C_ADDRESSINGMODE_7BIT,ownAddress,master); +#ifndef STM32F1xx if(master == false){ // i2c_attachSlaveTxEvent(&_i2c, reinterpret_cast(&TwoWire::onRequestService)); // i2c_attachSlaveRxEvent(&_i2c, reinterpret_cast(&TwoWire::onReceiveService)); @@ -88,6 +89,7 @@ void TwoWire::begin(uint8_t address) i2c_attachSlaveTxEvent(&_i2c, onRequestService); i2c_attachSlaveRxEvent(&_i2c, onReceiveService); } +#endif } void TwoWire::begin(int address) @@ -109,6 +111,8 @@ uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity, uint32_t iaddres { UNUSED(sendStop); if (master == true) { + //NOTE: do not work with STM32F1xx boards (latest HAL version: 1.0.4) +#ifndef STM32F1xx if (isize > 0) { // send internal address; this mode allows sending a repeated start to access // some devices' internal registers. This function is executed by the hardware @@ -127,6 +131,10 @@ uint8_t TwoWire::requestFrom(uint8_t address, uint8_t quantity, uint32_t iaddres } endTransmission(false); } +#else + UNUSED(iaddress); + UNUSED(isize); +#endif /* !STM32F1xx */ // clamp to buffer length if(quantity > BUFFER_LENGTH){ @@ -369,12 +377,22 @@ void TwoWire::onRequestService(void) void TwoWire::onReceive( void (*function)(int) ) { user_onReceive = function; + +#ifdef STM32F1xx + //Enable slave receive IT + i2c_attachSlaveRxEvent(&_i2c, onReceiveService); +#endif } // sets function called on slave read void TwoWire::onRequest( void (*function)(void) ) { user_onRequest = function; + +#ifdef STM32F1xx + //Enable slave transmit IT + i2c_attachSlaveTxEvent(&_i2c, onRequestService); +#endif } // Preinstantiate Objects ////////////////////////////////////////////////////// diff --git a/libraries/Wire/examples/master_reader_writer/master_reader_writer.ino b/libraries/Wire/examples/master_reader_writer/master_reader_writer.ino new file mode 100644 index 0000000000..6f73acf217 --- /dev/null +++ b/libraries/Wire/examples/master_reader_writer/master_reader_writer.ino @@ -0,0 +1,44 @@ +/* Wire Master Reader Writer +by Wi6Labs + +Demonstrates use of the Wire library, particullary with STM32F1xx boards. +Reads/writes data from/to an I2C/TWI slave device. +Refer to the "Wire Slave Sender Receiver" example for use with this. + +Created 27 June 2017 + +This example code is in the public domain. +*/ + +#include + +#define I2C_ADDR 2 + +byte x = 0; + +void setup() +{ + Wire.begin(); // join i2c bus (address optional for master) + Serial.begin(9600); // start serial for output +} + +void loop() +{ + Wire.requestFrom(I2C_ADDR, 6); // request 6 bytes from slave device + + while(Wire.available()) // slave may send less than requested + { + char c = Wire.read(); // receive a byte as character + Serial.print(c); // print the character + } + + delay(10); + + Wire.beginTransmission(I2C_ADDR); // transmit to device + Wire.write("x is "); // sends five bytes + Wire.write(x); // sends one byte + Wire.endTransmission(); // stop transmitting + x++; + + delay(1000); +} diff --git a/libraries/Wire/examples/slave_sender_receiver/slave_sender_receiver.ino b/libraries/Wire/examples/slave_sender_receiver/slave_sender_receiver.ino new file mode 100644 index 0000000000..92912961f9 --- /dev/null +++ b/libraries/Wire/examples/slave_sender_receiver/slave_sender_receiver.ino @@ -0,0 +1,70 @@ +/* Wire Slave Receiver +by Wi6Labs + +Demonstrates use of the Wire library, particullary with STM32F1xx boards where +we can't use slave Tx & Rx mode in same time. +Receives/sends data as an I2C/TWI slave device. +Refer to the "Wire Master Reader Writer" example for use with this. + +Created 27 June 2017 + +This example code is in the public domain. +*/ + +#include + +#define SLAVE_MODE_RX 0 +#define SLAVE_MODE_TX 1 + +#define I2C_ADDR 2 + +int w_r_mode = SLAVE_MODE_TX; +bool switch_mode = false; + +void setup() +{ + Wire.begin(I2C_ADDR); // join i2c bus with address #4 + Wire.onRequest(requestEvent); // register event + Serial.begin(9600); // start serial for output +} + +void loop() +{ + if(switch_mode == true) { + switch_mode = false; + Wire.end(); + Wire.begin(I2C_ADDR); + if(w_r_mode == SLAVE_MODE_TX) { + Wire.onRequest(requestEvent); // register event + } else { + Wire.onReceive(receiveEvent); // register event + } + } +} + +// function that executes whenever data is received from master +// this function is registered as an event, see setup() +void receiveEvent(int howMany) +{ + while(1 < Wire.available()) // loop through all but the last + { + char c = Wire.read(); // receive byte as a character + Serial.print(c); // print the character + } + int x = Wire.read(); // receive byte as an integer + Serial.println(x); // print the integer + + switch_mode = true; + w_r_mode = SLAVE_MODE_TX; +} + +// function that executes whenever data is requested by master +// this function is registered as an event, see setup() +void requestEvent() +{ + Wire.write("hello "); // respond with message of 6 bytes + // as expected by master + + switch_mode = true; + w_r_mode = SLAVE_MODE_RX; +} diff --git a/system/STM32F1xx/system_stm32f1xx.c b/system/STM32F1xx/system_stm32f1xx.c new file mode 100644 index 0000000000..a582b704d1 --- /dev/null +++ b/system/STM32F1xx/system_stm32f1xx.c @@ -0,0 +1,446 @@ +/** + ****************************************************************************** + * @file system_stm32f1xx.c + * @author MCD Application Team + * @version V4.1.0 + * @date 29-April-2016 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File. + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * factors, AHB/APBx prescalers and Flash settings). + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f1xx_xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (8 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f1xx_xx.s" file, to + * configure the system clock before to branch to main program. + * + * 4. The default value of HSE crystal is set to 8 MHz (or 25 MHz, depending on + * the product used), refer to "HSE_VALUE". + * When HSE is used as system clock source, directly or through PLL, and you + * are using different crystal you have to adapt the HSE value to your own + * configuration. + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f1xx_system + * @{ + */ + +/** @addtogroup STM32F1xx_System_Private_Includes + * @{ + */ + +#include "stm32f1xx.h" + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_Defines + * @{ + */ + +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz. + This value can be provided and adapted by the user application. */ +#endif /* HSI_VALUE */ + +/*!< Uncomment the following line if you need to use external SRAM */ +#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG) +/* #define DATA_IN_ExtSRAM */ +#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */ + +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#ifndef VECT_TAB_OFFSET +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +#endif + + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_Variables + * @{ + */ + +/******************************************************************************* +* Clock Definitions +*******************************************************************************/ +uint32_t SystemCoreClock = F_CPU; /*!< System Clock Frequency (Core Clock) */ + +const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_FunctionPrototypes + * @{ + */ + +#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG) +#ifdef DATA_IN_ExtSRAM + static void SystemInit_ExtMemCtl(void); +#endif /* DATA_IN_ExtSRAM */ +#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */ + +/** + * @} + */ + +/** @addtogroup STM32F1xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemCoreClock variable. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +void SystemInit (void) +{ + /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ +#if !defined(STM32F105xC) && !defined(STM32F107xC) + RCC->CFGR &= (uint32_t)0xF8FF0000; +#else + RCC->CFGR &= (uint32_t)0xF0FF0000; +#endif /* STM32F105xC */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + +#if defined(STM32F105xC) || defined(STM32F107xC) + /* Reset PLL2ON and PLL3ON bits */ + RCC->CR &= (uint32_t)0xEBFFFFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x00FF0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#elif defined(STM32F100xB) || defined(STM32F100xE) + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#else + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; +#endif /* STM32F105xC */ + +#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG) + #ifdef DATA_IN_ExtSRAM + SystemInit_ExtMemCtl(); + #endif /* DATA_IN_ExtSRAM */ +#endif + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value + * 8 MHz or 25 MHz, depending on the product used), user has to ensure + * that HSE_VALUE is same as the real frequency of the crystal used. + * Otherwise, this function may have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0; + +#if defined(STM32F105xC) || defined(STM32F107xC) + uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0; +#endif /* STM32F105xC */ + +#if defined(STM32F100xB) || defined(STM32F100xE) + uint32_t prediv1factor = 0; +#endif /* STM32F100xB or STM32F100xE */ + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + +#if !defined(STM32F105xC) && !defined(STM32F107xC) + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { + #if defined(STM32F100xB) || defined(STM32F100xE) + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + #else + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET) + {/* HSE oscillator clock divided by 2 */ + SystemCoreClock = (HSE_VALUE >> 1) * pllmull; + } + else + { + SystemCoreClock = HSE_VALUE * pllmull; + } + #endif + } +#else + pllmull = pllmull >> 18; + + if (pllmull != 0x0D) + { + pllmull += 2; + } + else + { /* PLL multiplication factor = PLL input clock * 6.5 */ + pllmull = 13 / 2; + } + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + {/* PREDIV1 selected as PLL clock entry */ + + /* Get PREDIV1 clock source and division factor */ + prediv1source = RCC->CFGR2 & RCC_CFGR2_PREDIV1SRC; + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + + if (prediv1source == 0) + { + /* HSE oscillator clock selected as PREDIV1 clock entry */ + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } + else + {/* PLL2 clock selected as PREDIV1 clock entry */ + + /* Get PREDIV2 division factor and PLL2 multiplication factor */ + prediv2factor = ((RCC->CFGR2 & RCC_CFGR2_PREDIV2) >> 4) + 1; + pll2mull = ((RCC->CFGR2 & RCC_CFGR2_PLL2MUL) >> 8 ) + 2; + SystemCoreClock = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull; + } + } +#endif /* STM32F105xC */ + break; + + default: + SystemCoreClock = HSI_VALUE; + break; + } + + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +#if defined(STM32F100xE) || defined(STM32F101xE) || defined(STM32F101xG) || defined(STM32F103xE) || defined(STM32F103xG) +/** + * @brief Setup the external memory controller. Called in startup_stm32f1xx.s + * before jump to __main + * @param None + * @retval None + */ +#ifdef DATA_IN_ExtSRAM +/** + * @brief Setup the external memory controller. + * Called in startup_stm32f1xx_xx.s/.c before jump to main. + * This function configures the external SRAM mounted on STM3210E-EVAL + * board (STM32 High density devices). This SRAM will be used as program + * data memory (including heap and stack). + * @param None + * @retval None + */ +void SystemInit_ExtMemCtl(void) +{ + __IO uint32_t tmpreg; + /*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is + required, then adjust the Register Addresses */ + + /* Enable FSMC clock */ + RCC->AHBENR = 0x00000114; + + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_FSMCEN); + + /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */ + RCC->APB2ENR = 0x000001E0; + + /* Delay after an RCC peripheral clock enabling */ + tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_IOPDEN); + + (void)(tmpreg); + +/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/ +/*---------------- SRAM Address lines configuration -------------------------*/ +/*---------------- NOE and NWE configuration --------------------------------*/ +/*---------------- NE3 configuration ----------------------------------------*/ +/*---------------- NBL0, NBL1 configuration ---------------------------------*/ + + GPIOD->CRL = 0x44BB44BB; + GPIOD->CRH = 0xBBBBBBBB; + + GPIOE->CRL = 0xB44444BB; + GPIOE->CRH = 0xBBBBBBBB; + + GPIOF->CRL = 0x44BBBBBB; + GPIOF->CRH = 0xBBBB4444; + + GPIOG->CRL = 0x44BBBBBB; + GPIOG->CRH = 0x444B4B44; + +/*---------------- FSMC Configuration ---------------------------------------*/ +/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/ + + FSMC_Bank1->BTCR[4] = 0x00001091; + FSMC_Bank1->BTCR[5] = 0x00110212; +} +#endif /* DATA_IN_ExtSRAM */ +#endif /* STM32F100xE || STM32F101xE || STM32F101xG || STM32F103xE || STM32F103xG */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/variants/NUCLEO_F103RB/PeripheralPins.c b/variants/NUCLEO_F103RB/PeripheralPins.c new file mode 100644 index 0000000000..c0aceead20 --- /dev/null +++ b/variants/NUCLEO_F103RB/PeripheralPins.c @@ -0,0 +1,207 @@ +/* + ******************************************************************************* + * Copyright (c) 2016, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +// ===== +// Note: Commented lines are alternative possibilities which are not used per default. +// If you change them, you will have to know what you do +// ===== + + +//*** ADC *** + +const PinMap PinMap_ADC[] = { + {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 +// {PA0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 + {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 +// {PA1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - STLink Tx +// {PA2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - STLink Rx +// {PA3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 + {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 +// {PA4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 + {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 +// {PA5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 + {PA6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 +// {PA6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 + {PA7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 +// {PA7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 + {PB0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 +// {PB0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 + {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 +// {PB1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 + {PC0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 +// {PC0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 + {PC1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 +// {PC1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 + {PC2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 +// {PC2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 + {PC3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 +// {PC3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 + {PC4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 +// {PC4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 + {PC5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 +// {PC5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 + {NC, NP, 0} +}; + +//*** I2C *** + +const PinMap PinMap_I2C_SDA[] = { + {PB7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 0)}, + {PB9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 2)}, // GPIO_Remap_I2C1 + {PB11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 0)}, + {NC, NP, 0} +}; + +const PinMap PinMap_I2C_SCL[] = { + {PB6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 0)}, + {PB8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 2)}, // GPIO_Remap_I2C1 + {PB10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, 0)}, + {NC, NP, 0} +}; + +//*** PWM *** + +const PinMap PinMap_PWM[] = { + {PA0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 1, 0)}, // TIM2_CH1 + {PA1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 2, 0)}, // TIM2_CH2 +// {PA2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 3, 0)}, // TIM2_CH3 - STLink Rx +// {PA3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 4, 0)}, // TIM2_CH4 - STLink Tx + {PA6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 1, 0)}, // TIM3_CH1 +// {PA7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 6, 1, 1)}, // TIM1_CH1N - GPIO_PartialRemap_TIM1 + {PA7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 2, 0)}, // TIM3_CH2 + {PA8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 1, 0)}, // TIM1_CH1 + {PA9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 2, 0)}, // TIM1_CH2 + {PA10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 3, 0)}, // TIM1_CH3 + {PA11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 4, 0)}, // TIM1_CH4 + {PA15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 8, 1, 0)}, // TIM2_CH1 - GPIO_FullRemap_TIM2 +// {PB0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 6, 2, 1)}, // TIM1_CH2N - GPIO_PartialRemap_TIM1 + {PB0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 3, 0)}, // TIM3_CH3 +// {PB1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 6, 3, 1)}, // TIM1_CH3N - GPIO_PartialRemap_TIM1 + {PB1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 4, 0)}, // TIM3_CH4 + {PB3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 8, 2, 0)}, // TIM2_CH2 - GPIO_FullRemap_TIM2 + {PB4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 7, 1, 0)}, // TIM3_CH1 - GPIO_PartialRemap_TIM3 + {PB5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 7, 2, 0)}, // TIM3_CH2 - GPIO_PartialRemap_TIM3 + {PB6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 1, 0)}, // TIM4_CH1 + {PB7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 2, 0)}, // TIM4_CH2 + {PB8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 3, 0)}, // TIM4_CH3 + {PB9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 4, 0)}, // TIM4_CH4 + {PB10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 8, 3, 0)}, // TIM2_CH3 - GPIO_FullRemap_TIM2 + {PB11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 8, 4, 0)}, // TIM2_CH4 - GPIO_FullRemap_TIM2 + {PB13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 1, 1)}, // TIM1_CH1N + {PB14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 2, 1)}, // TIM1_CH2N + {PB15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 0, 3, 1)}, // TIM1_CH3N + {PC6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 9, 1, 0)}, // TIM3_CH1 - GPIO_FullRemap_TIM3 + {PC7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 9, 2, 0)}, // TIM3_CH2 - GPIO_FullRemap_TIM3 + {PC8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 9, 3, 0)}, // TIM3_CH3 - GPIO_FullRemap_TIM3 + {PC9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, 9, 4, 0)}, // TIM3_CH4 - GPIO_FullRemap_TIM3 + {NC, NP, 0} +}; + +//*** SERIAL *** + +const PinMap PinMap_UART_TX[] = { + {PA2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PA9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 3)}, // GPIO_Remap_USART1 + {PB10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PC10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 5)}, // GPIO_PartialRemap_USART3 + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PA10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 3)}, // GPIO_Remap_USART1 + {PB11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PC11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 5)}, // GPIO_PartialRemap_USART3 + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RTS[] = { + {PA1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PA12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_CTS[] = { + {PA0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PA11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +//*** SPI *** + +const PinMap PinMap_SPI_MOSI[] = { + {PA7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 1)}, // GPIO_Remap_SPI1 + {PB15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 1)}, // GPIO_Remap_SPI1 + {PB14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 1)}, // GPIO_Remap_SPI1 + {PB13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {PA15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 1)}, // GPIO_Remap_SPI1 + {PB12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, 0)}, + {NC, NP, 0} +}; + +//*** CAN *** + +const PinMap PinMap_CAN_RD[] = { + {PA11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, 0)}, + {PB8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, 10)}, // Remap CAN_RX to PB_9 + {NC, NP, 0} +}; + +const PinMap PinMap_CAN_TD[] = { + {PA12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, 0)}, + {PB9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, 10)}, // Remap CAN_TX to PB_9 + {NC, NP, 0} +}; diff --git a/variants/NUCLEO_F103RB/ldscript.ld b/variants/NUCLEO_F103RB/ldscript.ld new file mode 100644 index 0000000000..1608bb0834 --- /dev/null +++ b/variants/NUCLEO_F103RB/ldscript.ld @@ -0,0 +1,181 @@ +/** + ****************************************************************************** + * @file STM32F103RB_FLASH.ld + * @author WI6LABS + * @version V1.0.1 + * @date 21-September-2016 + * @brief Linker script for STM32F103RB Device with + * 128KByte FLASH, 20KByte RAM + * + * Set heap size, stack size and stack location according + * to application requirements. + * + * Set memory bank area and size if external memory is used. + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + /* Entry Point */ + ENTRY(Reset_Handler) + + /* Highest address of the user mode stack */ + _estack = 0x20005000; /* end of RAM */ + /* Generate a link error if heap and stack don't fit into RAM */ + _Min_Heap_Size = 0x200; /* required amount of heap */ + _Min_Stack_Size = 0x400; /* required amount of stack */ + + /* Specify the memory areas */ + MEMORY + { + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K + FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K + } + + /* Define output sections */ + SECTIONS + { + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } + } diff --git a/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h b/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h new file mode 100644 index 0000000000..505534a30e --- /dev/null +++ b/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h @@ -0,0 +1,367 @@ +/** + ****************************************************************************** + * @file stm32f1xx_hal_conf.h + * @author MCD Application Team + * @version V1.0.4 + * @date 29-April-2016 + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32f1xx_hal_conf.h. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F1xx_HAL_CONF_H +#define __STM32F1xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_PCCARD_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED +//#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_UART_MODULE_ENABLED +//#define HAL_USART_MODULE_ENABLED +//#define HAL_WWDG_MODULE_ENABLED + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) +#if defined(USE_STM3210C_EVAL) + #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#else + #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ +#endif +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */ +#define USE_RTOS 0 +#define PREFETCH_ENABLE 1 + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/*#define USE_FULL_ASSERT 1*/ + + +/* ################## Ethernet peripheral configuration ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2 +#define MAC_ADDR1 0 +#define MAC_ADDR2 0 +#define MAC_ADDR3 0 +#define MAC_ADDR4 0 +#define MAC_ADDR5 0 + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)8) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)4) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848 PHY Address*/ +#define DP83848_PHY_ADDRESS 0x01 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x000000FF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x10) /*!< PHY status register Offset */ +#define PHY_MICR ((uint16_t)0x11) /*!< MII Interrupt Control Register */ +#define PHY_MISR ((uint16_t)0x12) /*!< MII Interrupt Status and Misc. Control Register */ + +#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ +#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ + +#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ +#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ + +#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ +#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */ + + + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f1xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f1xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f1xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f1xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f1xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f1xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f1xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f1xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f1xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f1xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f1xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f1xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f1xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f1xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f1xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f1xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f1xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f1xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f1xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f1xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f1xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f1xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f1xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f1xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f1xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f1xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f1xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f1xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f1xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F1xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/variants/NUCLEO_F103RB/variant.cpp b/variants/NUCLEO_F103RB/variant.cpp new file mode 100644 index 0000000000..4d2e9d2672 --- /dev/null +++ b/variants/NUCLEO_F103RB/variant.cpp @@ -0,0 +1,199 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PA3, //D0 + PA2, //D1 + PA10, //D2 + PB3, //D3 + PB5, //D4 + PB4, //D5 + PB10, //D6 + PA8, //D7 + PA9, //D8 + PC7, //D9 + PB6, //D10 + PA7, //D11 + PA6, //D12 + PA5, //D13 - LED + PB9, //D14 + PB8, //D15 + // ST Morpho + // CN7 Left Side + PC10, //D16 + PC12, //D17 + NC, //D18 - BOOT0 + PA13, //D19 - SWD + PA14, //D20 - SWD + PA15, //D21 + PB7, //D22 + PC13, //D23 + PC14, //D24 + PC15, //D25 + PD0, //D26 + PD1, //D27 + PC2, //D28 + PC3, //D29 + // CN7 Right Side + PC11, //D30 + PD2, //D31 + // CN10 Left Side + PC9, //D32 + // CN10 Right side + PC8, //D33 + PC6, //D34 + PC5, //D35 + PA12, //D36 + PA11, //D37 + PB12, //D38 + PB11, //D39 + PB2, //D40 + PB1, //D41 + PB15, //D42 + PB14, //D43 + PB13, //D44 + PC4, //D45 + PA0, //D46/A0 + PA1, //D47/A1 + PA4, //D48/A2 + PB0, //D49/A3 + PC1, //D50/A4 + PC0, //D51/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D52/A6 = D11 + PA6, //D53/A7 = D12 + PA5, //D54/A8 = D13 + PC2, //D55/A9 = D28 + PC3, //D56/A10 = D29 + PB1, //D57/A11 = D41 + PC4 //D58/A12 = D45 +}; + +#ifdef __cplusplus +} +#endif + +/* + * UART objects + */ + +HardwareSerial Serial(PA3, PA2); // Connected to ST-Link +#ifdef ENABLE_SERIAL1 +HardwareSerial Serial1(PA10, PA9); +#endif +#ifdef ENABLE_SERIAL2 +HardwareSerial Serial2(PC11, PC10); //Morpho pins +#endif + +void serialEvent() __attribute__((weak)); +void serialEvent() { } +#ifdef ENABLE_SERIAL1 +void serialEvent1() __attribute__((weak)); +void serialEvent1() { } +#endif +#ifdef ENABLE_SERIAL2 +void serialEvent2() __attribute__((weak)); +void serialEvent2() { } +#endif + +void serialEventRun(void) +{ + if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 + if (Serial1.available()) serialEvent1(); +#endif +#ifdef ENABLE_SERIAL2 + if (Serial2.available()) serialEvent2(); +#endif +} + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 72000000 + * HCLK(Hz) = 72000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 2 + * APB2 Prescaler = 1 + * PLL_Source = HSE + * PLL_Mul = 9 + * Flash Latency(WS) = 2 + * ADC Prescaler = 6 + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInit; + + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + while(1); + } + + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) + { + while(1); + } + + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; + PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + while(1); + } + + HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000); + + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); +} + +#ifdef __cplusplus +} +#endif diff --git a/variants/NUCLEO_F103RB/variant.h b/variants/NUCLEO_F103RB/variant.h new file mode 100644 index 0000000000..d678ed4447 --- /dev/null +++ b/variants/NUCLEO_F103RB/variant.h @@ -0,0 +1,144 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "Arduino.h" + +#ifdef __cplusplus +extern "C"{ +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ +#include "PeripheralPins.h" + +extern const PinName digitalPin[]; + +enum { + D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, + D10, D11, D12, D13, D14, D15, D16, D17, D18, D19, + D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, + D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, + D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, + D50, D51, D52, D53, D54, D55, D56, D57, D58, + DEND +}; + +enum { + A_START_AFTER = D45, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, A12, + AEND +}; + +//ADC resolution is 12bits +#define ADC_RESOLUTION 12 +#define DACC_RESOLUTION 12 + +//PWR resolution +#define PWM_RESOLUTION 8 +#define PWM_FREQUENCY 1000 +#define PWM_MAX_DUTY_CYCLE 255 + +//On-board LED pin number +#define LED_BUILTIN 13 +#define LED_GREEN LED_BUILTIN + +//On-board user button +#define USER_BTN 23 + +//SPI definitions +//define 16 channels. As many channel as digital IOs +#define SPI_CHANNELS_NUM 16 + +//default chip salect pin +#define BOARD_SPI_DEFAULT_SS 10 + +//In case SPI CS channel is not used we define a default one +#define BOARD_SPI_OWN_SS SPI_CHANNELS_NUM + +#define SS BOARD_SPI_DEFAULT_SS +#define SS1 4 +#define SS2 7 +#define SS3 8 +#define MOSI 11 +#define MISO 12 +#define SCLK 13 +#define SCK SCLK + +//I2C Definitions +#define SDA 14 +#define SCL 15 + +//Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM. +#define TIMER_TONE TIM4 +#define TIMER_UART_EMULATED TIM4 + +//Do not use basic timer: OC is required +#define TIMER_SERVO TIM2 //TODO: advanced-control timers don't work + +#define DEBUG_UART ((USART_TypeDef *) USART2) + +// Serial Pin Firmata +#define PIN_SERIAL_RX 0 +#define PIN_SERIAL_TX 1 +#define PIN_SERIAL1_RX 2 +#define PIN_SERIAL1_TX 8 +#define PIN_SERIAL2_RX 30 +#define PIN_SERIAL2_TX 16 + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern HardwareSerial Serial; +extern HardwareSerial Serial1; +extern HardwareSerial Serial2; + +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */