[NUCLEO_F030R8] reorg hal folder

pull/877/head
ohagendorf 2015-01-24 20:02:29 +01:00
parent 2942309fd4
commit aadd0bcb13
8 changed files with 242 additions and 768 deletions

View File

@ -1,206 +0,0 @@
/* mbed Microcontroller Library
*******************************************************************************
* Copyright (c) 2014, 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 "pwmout_api.h"
#if DEVICE_PWMOUT
#include "cmsis.h"
#include "pinmap.h"
#include "mbed_error.h"
#include "PeripheralPins.h"
static TIM_HandleTypeDef TimHandle;
void pwmout_init(pwmout_t* obj, PinName pin)
{
// Get the peripheral name from the pin and assign it to the object
obj->pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
if (obj->pwm == (PWMName)NC) {
error("PWM error: pinout mapping failed.");
}
// Enable TIM clock
if (obj->pwm == PWM_3) __TIM3_CLK_ENABLE();
if (obj->pwm == PWM_14) __TIM14_CLK_ENABLE();
if (obj->pwm == PWM_15) __TIM15_CLK_ENABLE();
if (obj->pwm == PWM_16) __TIM16_CLK_ENABLE();
if (obj->pwm == PWM_17) __TIM17_CLK_ENABLE();
// Configure GPIO
pinmap_pinout(pin, PinMap_PWM);
obj->pin = pin;
obj->period = 0;
obj->pulse = 0;
pwmout_period_us(obj, 20000); // 20 ms per default
}
void pwmout_free(pwmout_t* obj)
{
// Configure GPIO
pin_function(obj->pin, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0));
}
void pwmout_write(pwmout_t* obj, float value)
{
TIM_OC_InitTypeDef sConfig;
int channel = 0;
int complementary_channel = 0;
TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
if (value < (float)0.0) {
value = 0.0;
} else if (value > (float)1.0) {
value = 1.0;
}
obj->pulse = (uint32_t)((float)obj->period * value);
// Configure channels
sConfig.OCMode = TIM_OCMODE_PWM1;
sConfig.Pulse = obj->pulse;
sConfig.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfig.OCNPolarity = TIM_OCNPOLARITY_HIGH;
sConfig.OCFastMode = TIM_OCFAST_DISABLE;
sConfig.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET;
switch (obj->pin) {
// Channels 1
case PA_4:
case PA_6:
case PB_1:
case PB_4:
case PB_8:
case PB_9:
case PB_14:
case PC_6:
channel = TIM_CHANNEL_1;
break;
// Channels 1N
case PB_6:
case PB_7:
channel = TIM_CHANNEL_1;
complementary_channel = 1;
break;
// Channels 2
case PA_7:
case PB_5:
case PB_15:
case PC_7:
channel = TIM_CHANNEL_2;
break;
// Channels 3
case PB_0:
case PC_8:
channel = TIM_CHANNEL_3;
break;
// Channels 4
case PC_9:
channel = TIM_CHANNEL_4;
break;
default:
return;
}
HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel);
if (complementary_channel) {
HAL_TIMEx_PWMN_Start(&TimHandle, channel);
} else {
HAL_TIM_PWM_Start(&TimHandle, channel);
}
}
float pwmout_read(pwmout_t* obj)
{
float value = 0;
if (obj->period > 0) {
value = (float)(obj->pulse) / (float)(obj->period);
}
return ((value > (float)1.0) ? (float)(1.0) : (value));
}
void pwmout_period(pwmout_t* obj, float seconds)
{
pwmout_period_us(obj, seconds * 1000000.0f);
}
void pwmout_period_ms(pwmout_t* obj, int ms)
{
pwmout_period_us(obj, ms * 1000);
}
void pwmout_period_us(pwmout_t* obj, int us)
{
TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
float dc = pwmout_read(obj);
__HAL_TIM_DISABLE(&TimHandle);
// Update the SystemCoreClock variable
SystemCoreClockUpdate();
TimHandle.Init.Period = us - 1;
TimHandle.Init.Prescaler = (uint16_t)(SystemCoreClock / 1000000) - 1; // 1 µs tick
TimHandle.Init.ClockDivision = 0;
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
HAL_TIM_PWM_Init(&TimHandle);
// Set duty cycle again
pwmout_write(obj, dc);
// Save for future use
obj->period = us;
__HAL_TIM_ENABLE(&TimHandle);
}
void pwmout_pulsewidth(pwmout_t* obj, float seconds)
{
pwmout_pulsewidth_us(obj, seconds * 1000000.0f);
}
void pwmout_pulsewidth_ms(pwmout_t* obj, int ms)
{
pwmout_pulsewidth_us(obj, ms * 1000);
}
void pwmout_pulsewidth_us(pwmout_t* obj, int us)
{
float value = (float)us / (float)obj->period;
pwmout_write(obj, value);
}
#endif

View File

@ -1,324 +0,0 @@
/* mbed Microcontroller Library
*******************************************************************************
* Copyright (c) 2014, 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 "mbed_assert.h"
#include "serial_api.h"
#if DEVICE_SERIAL
#include "cmsis.h"
#include "pinmap.h"
#include <string.h>
#include "PeripheralPins.h"
#define UART_NUM (2)
static uint32_t serial_irq_ids[UART_NUM] = {0, 0};
static uart_irq_handler irq_handler;
UART_HandleTypeDef UartHandle;
int stdio_uart_inited = 0;
serial_t stdio_uart;
static void init_uart(serial_t *obj)
{
UartHandle.Instance = (USART_TypeDef *)(obj->uart);
UartHandle.Init.BaudRate = obj->baudrate;
UartHandle.Init.WordLength = obj->databits;
UartHandle.Init.StopBits = obj->stopbits;
UartHandle.Init.Parity = obj->parity;
UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
if (obj->pin_rx == NC) {
UartHandle.Init.Mode = UART_MODE_TX;
} else if (obj->pin_tx == NC) {
UartHandle.Init.Mode = UART_MODE_RX;
} else {
UartHandle.Init.Mode = UART_MODE_TX_RX;
}
// Disable the reception overrun detection
UartHandle.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_RXOVERRUNDISABLE_INIT;
UartHandle.AdvancedInit.OverrunDisable = UART_ADVFEATURE_OVERRUN_DISABLE;
HAL_UART_Init(&UartHandle);
}
void serial_init(serial_t *obj, PinName tx, PinName rx)
{
// Determine the UART to use (UART_1, UART_2, ...)
UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX);
UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX);
// Get the peripheral name (UART_1, UART_2, ...) from the pin and assign it to the object
obj->uart = (UARTName)pinmap_merge(uart_tx, uart_rx);
MBED_ASSERT(obj->uart != (UARTName)NC);
// Enable USART clock
if (obj->uart == UART_1) {
__USART1_CLK_ENABLE();
obj->index = 0;
}
if (obj->uart == UART_2) {
__USART2_CLK_ENABLE();
obj->index = 1;
}
// Configure the UART pins
pinmap_pinout(tx, PinMap_UART_TX);
pinmap_pinout(rx, PinMap_UART_RX);
if (tx != NC) {
pin_mode(tx, PullUp);
}
if (rx != NC) {
pin_mode(rx, PullUp);
}
// Configure UART
obj->baudrate = 9600;
obj->databits = UART_WORDLENGTH_8B;
obj->stopbits = UART_STOPBITS_1;
obj->parity = UART_PARITY_NONE;
obj->pin_tx = tx;
obj->pin_rx = rx;
init_uart(obj);
// For stdio management
if (obj->uart == STDIO_UART) {
stdio_uart_inited = 1;
memcpy(&stdio_uart, obj, sizeof(serial_t));
}
}
void serial_free(serial_t *obj)
{
// Reset UART and disable clock
if (obj->uart == UART_1) {
__USART1_FORCE_RESET();
__USART1_RELEASE_RESET();
__USART1_CLK_DISABLE();
}
if (obj->uart == UART_2) {
__USART2_FORCE_RESET();
__USART2_RELEASE_RESET();
__USART2_CLK_DISABLE();
}
// Configure GPIOs
pin_function(obj->pin_tx, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0));
pin_function(obj->pin_rx, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0));
serial_irq_ids[obj->index] = 0;
}
void serial_baud(serial_t *obj, int baudrate)
{
obj->baudrate = baudrate;
init_uart(obj);
}
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits)
{
if (data_bits == 9) {
obj->databits = UART_WORDLENGTH_9B;
} else {
obj->databits = UART_WORDLENGTH_8B;
}
switch (parity) {
case ParityOdd:
case ParityForced0:
obj->parity = UART_PARITY_ODD;
break;
case ParityEven:
case ParityForced1:
obj->parity = UART_PARITY_EVEN;
break;
default: // ParityNone
obj->parity = UART_PARITY_NONE;
break;
}
if (stop_bits == 2) {
obj->stopbits = UART_STOPBITS_2;
} else {
obj->stopbits = UART_STOPBITS_1;
}
init_uart(obj);
}
/******************************************************************************
* INTERRUPTS HANDLING
******************************************************************************/
static void uart_irq(UARTName name, int id)
{
UartHandle.Instance = (USART_TypeDef *)name;
if (serial_irq_ids[id] != 0) {
if (__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_TC) != RESET) {
irq_handler(serial_irq_ids[id], TxIrq);
__HAL_UART_CLEAR_IT(&UartHandle, UART_FLAG_TC);
}
if (__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_RXNE) != RESET) {
irq_handler(serial_irq_ids[id], RxIrq);
volatile uint32_t tmpval = UartHandle.Instance->RDR; // Clear RXNE bit
}
}
}
static void uart1_irq(void)
{
uart_irq(UART_1, 0);
}
static void uart2_irq(void)
{
uart_irq(UART_2, 1);
}
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id)
{
irq_handler = handler;
serial_irq_ids[obj->index] = id;
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable)
{
IRQn_Type irq_n = (IRQn_Type)0;
uint32_t vector = 0;
UartHandle.Instance = (USART_TypeDef *)(obj->uart);
if (obj->uart == UART_1) {
irq_n = USART1_IRQn;
vector = (uint32_t)&uart1_irq;
}
if (obj->uart == UART_2) {
irq_n = USART2_IRQn;
vector = (uint32_t)&uart2_irq;
}
if (enable) {
if (irq == RxIrq) {
__HAL_UART_ENABLE_IT(&UartHandle, UART_IT_RXNE);
} else { // TxIrq
__HAL_UART_ENABLE_IT(&UartHandle, UART_IT_TC);
}
NVIC_SetVector(irq_n, vector);
NVIC_EnableIRQ(irq_n);
} else { // disable
int all_disabled = 0;
if (irq == RxIrq) {
__HAL_UART_DISABLE_IT(&UartHandle, UART_IT_RXNE);
// Check if TxIrq is disabled too
if ((UartHandle.Instance->CR1 & USART_CR1_TCIE) == 0) all_disabled = 1;
} else { // TxIrq
__HAL_UART_DISABLE_IT(&UartHandle, UART_IT_TC);
// Check if RxIrq is disabled too
if ((UartHandle.Instance->CR1 & USART_CR1_RXNEIE) == 0) all_disabled = 1;
}
if (all_disabled) NVIC_DisableIRQ(irq_n);
}
}
/******************************************************************************
* READ/WRITE
******************************************************************************/
int serial_getc(serial_t *obj)
{
USART_TypeDef *uart = (USART_TypeDef *)(obj->uart);
while (!serial_readable(obj));
return (int)(uart->RDR & (uint16_t)0xFF);
}
void serial_putc(serial_t *obj, int c)
{
USART_TypeDef *uart = (USART_TypeDef *)(obj->uart);
while (!serial_writable(obj));
uart->TDR = (uint32_t)(c & (uint16_t)0xFF);
}
int serial_readable(serial_t *obj)
{
int status;
UartHandle.Instance = (USART_TypeDef *)(obj->uart);
// Check if data is received
status = ((__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_RXNE) != RESET) ? 1 : 0);
return status;
}
int serial_writable(serial_t *obj)
{
int status;
UartHandle.Instance = (USART_TypeDef *)(obj->uart);
// Check if data is transmitted
status = ((__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_TXE) != RESET) ? 1 : 0);
return status;
}
void serial_clear(serial_t *obj)
{
UartHandle.Instance = (USART_TypeDef *)(obj->uart);
__HAL_UART_CLEAR_IT(&UartHandle, UART_FLAG_TC);
__HAL_UART_SEND_REQ(&UartHandle, UART_RXDATA_FLUSH_REQUEST);
}
void serial_pinout_tx(PinName tx)
{
pinmap_pinout(tx, PinMap_UART_TX);
}
void serial_break_set(serial_t *obj)
{
// [TODO]
}
void serial_break_clear(serial_t *obj)
{
// [TODO]
}
#endif

View File

@ -1,59 +0,0 @@
/* mbed Microcontroller Library
*******************************************************************************
* Copyright (c) 2014, 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 "sleep_api.h"
#if DEVICE_SLEEP
#include "cmsis.h"
void sleep(void)
{
// Stop HAL systick
HAL_SuspendTick();
// Request to enter SLEEP mode
HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI);
// Restart HAL systick
HAL_ResumeTick();
}
void deepsleep(void)
{
// Request to enter STOP mode with regulator in low power mode
HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI);
HAL_InitTick(TICK_INT_PRIORITY);
// After wake-up from STOP reconfigure the PLL
SetSysClock();
HAL_InitTick(TICK_INT_PRIORITY);
}
#endif

View File

@ -1,179 +0,0 @@
/* mbed Microcontroller Library
* Copyright (c) 2014, 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 <stddef.h>
#include "us_ticker_api.h"
#include "PeripheralNames.h"
// Timer selection:
#define TIM_MST TIM1
#define TIM_MST_UP_IRQ TIM1_BRK_UP_TRG_COM_IRQn
#define TIM_MST_OC_IRQ TIM1_CC_IRQn
#define TIM_MST_RCC __TIM1_CLK_ENABLE()
static TIM_HandleTypeDef TimMasterHandle;
static int us_ticker_inited = 0;
static volatile uint32_t SlaveCounter = 0;
static volatile uint32_t oc_int_part = 0;
static volatile uint16_t oc_rem_part = 0;
void set_compare(uint16_t count)
{
TimMasterHandle.Instance = TIM_MST;
// Set new output compare value
__HAL_TIM_SetCompare(&TimMasterHandle, TIM_CHANNEL_1, count);
// Enable IT
__HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_CC1);
}
// Used to increment the slave counter
static void tim_update_irq_handler(void)
{
TimMasterHandle.Instance = TIM_MST;
// Clear Update interrupt flag
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE);
SlaveCounter++;
}
}
// Used by interrupt system
static void tim_oc_irq_handler(void)
{
uint16_t cval = TIM_MST->CNT;
TimMasterHandle.Instance = TIM_MST;
// Clear CC1 interrupt flag
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1);
}
if (oc_rem_part > 0) {
set_compare(oc_rem_part); // Finish the remaining time left
oc_rem_part = 0;
} else {
if (oc_int_part > 0) {
set_compare(0xFFFF);
oc_rem_part = cval; // To finish the counter loop the next time
oc_int_part--;
} else {
us_ticker_irq_handler();
}
}
}
void us_ticker_init(void)
{
if (us_ticker_inited) return;
us_ticker_inited = 1;
// Enable timer clock
TIM_MST_RCC;
// Configure time base
TimMasterHandle.Instance = TIM_MST;
TimMasterHandle.Init.Period = 0xFFFF;
TimMasterHandle.Init.Prescaler = (uint32_t)(SystemCoreClock / 1000000) - 1; // 1 <20>s tick
TimMasterHandle.Init.ClockDivision = 0;
TimMasterHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
HAL_TIM_Base_Init(&TimMasterHandle);
// Configure interrupts
__HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_UPDATE);
// Update interrupt used for 32-bit counter
NVIC_SetVector(TIM_MST_UP_IRQ, (uint32_t)tim_update_irq_handler);
NVIC_EnableIRQ(TIM_MST_UP_IRQ);
// Output compare interrupt used for timeout feature
NVIC_SetVector(TIM_MST_OC_IRQ, (uint32_t)tim_oc_irq_handler);
NVIC_EnableIRQ(TIM_MST_OC_IRQ);
// Enable timer
HAL_TIM_Base_Start(&TimMasterHandle);
}
uint32_t us_ticker_read()
{
uint32_t counter, counter2;
if (!us_ticker_inited) us_ticker_init();
// A situation might appear when Master overflows right after Slave is read and before the
// new (overflowed) value of Master is read. Which would make the code below consider the
// previous (incorrect) value of Slave and the new value of Master, which would return a
// value in the past. Avoid this by computing consecutive values of the timer until they
// are properly ordered.
counter = (uint32_t)(SlaveCounter << 16);
counter += TIM_MST->CNT;
while (1) {
counter2 = (uint32_t)(SlaveCounter << 16);
counter2 += TIM_MST->CNT;
if (counter2 > counter) {
break;
}
counter = counter2;
}
return counter2;
}
void us_ticker_set_interrupt(timestamp_t timestamp)
{
int delta = (int)((uint32_t)timestamp - us_ticker_read());
uint16_t cval = TIM_MST->CNT;
if (delta <= 0) { // This event was in the past
us_ticker_irq_handler();
} else {
oc_int_part = (uint32_t)(delta >> 16);
oc_rem_part = (uint16_t)(delta & 0xFFFF);
if (oc_rem_part <= (0xFFFF - cval)) {
set_compare(cval + oc_rem_part);
oc_rem_part = 0;
} else {
set_compare(0xFFFF);
oc_rem_part = oc_rem_part - (0xFFFF - cval);
}
}
}
void us_ticker_disable_interrupt(void)
{
TimMasterHandle.Instance = TIM_MST;
__HAL_TIM_DISABLE_IT(&TimMasterHandle, TIM_IT_CC1);
}
void us_ticker_clear_interrupt(void)
{
TimMasterHandle.Instance = TIM_MST;
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1);
}
}

View File

@ -48,7 +48,9 @@ void pwmout_init(pwmout_t* obj, PinName pin)
} }
// Enable TIM clock // Enable TIM clock
#if defined(TIM1_BASE)
if (obj->pwm == PWM_1) __TIM1_CLK_ENABLE(); if (obj->pwm == PWM_1) __TIM1_CLK_ENABLE();
#endif
#if defined(TIM2_BASE) #if defined(TIM2_BASE)
if (obj->pwm == PWM_2) __TIM2_CLK_ENABLE(); if (obj->pwm == PWM_2) __TIM2_CLK_ENABLE();
#endif #endif
@ -99,6 +101,46 @@ void pwmout_write(pwmout_t* obj, float value)
sConfig.OCIdleState = TIM_OCIDLESTATE_RESET; sConfig.OCIdleState = TIM_OCIDLESTATE_RESET;
sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET; sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET;
#if defined (TARGET_STM32F030R8)
switch (obj->pin) {
// Channels 1
case PA_4:
case PA_6:
case PB_1:
case PB_4:
case PB_8:
case PB_9:
case PB_14:
case PC_6:
channel = TIM_CHANNEL_1;
break;
// Channels 1N
case PB_6:
case PB_7:
channel = TIM_CHANNEL_1;
complementary_channel = 1;
break;
// Channels 2
case PA_7:
case PB_5:
case PB_15:
case PC_7:
channel = TIM_CHANNEL_2;
break;
// Channels 3
case PB_0:
case PC_8:
channel = TIM_CHANNEL_3;
break;
// Channels 4
case PC_9:
channel = TIM_CHANNEL_4;
break;
default:
return;
}
#else
switch (obj->pin) { switch (obj->pin) {
// Channels 1 // Channels 1
case PA_2: case PA_2:
@ -145,6 +187,8 @@ void pwmout_write(pwmout_t* obj, float value)
return; return;
} }
#endif
HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel); HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel);
if (complementary_channel) { if (complementary_channel) {

View File

@ -42,6 +42,11 @@
static uint32_t serial_irq_ids[UART_NUM] = {0, 0, 0, 0, 0, 0, 0, 0}; static uint32_t serial_irq_ids[UART_NUM] = {0, 0, 0, 0, 0, 0, 0, 0};
#elif defined (TARGET_STM32F030R8)
#define UART_NUM (2)
static uint32_t serial_irq_ids[UART_NUM] = {0, 0};
#else #else
#define UART_NUM (4) #define UART_NUM (4)
@ -102,15 +107,19 @@ void serial_init(serial_t *obj, PinName tx, PinName rx)
obj->index = 1; obj->index = 1;
} }
#if defined USART3_BASE
if (obj->uart == UART_3) { if (obj->uart == UART_3) {
__USART3_CLK_ENABLE(); __USART3_CLK_ENABLE();
obj->index = 2; obj->index = 2;
} }
#endif
#if defined USART4_BASE
if (obj->uart == UART_4) { if (obj->uart == UART_4) {
__USART4_CLK_ENABLE(); __USART4_CLK_ENABLE();
obj->index = 3; obj->index = 3;
} }
#endif
#if defined USART5_BASE #if defined USART5_BASE
if (obj->uart == UART_5) { if (obj->uart == UART_5) {
@ -183,17 +192,21 @@ void serial_free(serial_t *obj)
__USART2_CLK_DISABLE(); __USART2_CLK_DISABLE();
} }
#if defined USART3_BASE
if (obj->uart == UART_3) { if (obj->uart == UART_3) {
__USART3_FORCE_RESET(); __USART3_FORCE_RESET();
__USART3_RELEASE_RESET(); __USART3_RELEASE_RESET();
__USART3_CLK_DISABLE(); __USART3_CLK_DISABLE();
} }
#endif
#if defined USART4_BASE
if (obj->uart == UART_4) { if (obj->uart == UART_4) {
__USART4_FORCE_RESET(); __USART4_FORCE_RESET();
__USART4_RELEASE_RESET(); __USART4_RELEASE_RESET();
__USART4_CLK_DISABLE(); __USART4_CLK_DISABLE();
} }
#endif
#if defined USART5_BASE #if defined USART5_BASE
if (obj->uart == UART_5) { if (obj->uart == UART_5) {
@ -301,15 +314,19 @@ static void uart2_irq(void)
uart_irq(UART_2, 1); uart_irq(UART_2, 1);
} }
#if defined USART3_BASE
static void uart3_irq(void) static void uart3_irq(void)
{ {
uart_irq(UART_3, 2); uart_irq(UART_3, 2);
} }
#endif
#if defined USART4_BASE
static void uart4_irq(void) static void uart4_irq(void)
{ {
uart_irq(UART_4, 3); uart_irq(UART_4, 3);
} }
#endif
#if defined USART5_BASE #if defined USART5_BASE
static void uart5_irq(void) static void uart5_irq(void)
@ -393,6 +410,8 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable)
vector = (uint32_t)&uart8_irq; vector = (uint32_t)&uart8_irq;
} }
#elif defined (TARGET_STM32F030R8)
#else #else
if (obj->uart == UART_3) { if (obj->uart == UART_3) {
irq_n = USART3_4_IRQn; irq_n = USART3_4_IRQn;

View File

@ -49,6 +49,18 @@ void sleep(void)
// Enable HAL tick and us_ticker update interrupts // Enable HAL tick and us_ticker update interrupts
__HAL_TIM_ENABLE_IT(&TimMasterHandle, (TIM_IT_CC2 | TIM_IT_UPDATE)); __HAL_TIM_ENABLE_IT(&TimMasterHandle, (TIM_IT_CC2 | TIM_IT_UPDATE));
} }
#elif defined(TARGET_STM32F030R8)
void sleep(void)
{
// Stop HAL systick
HAL_SuspendTick();
// Request to enter SLEEP mode
HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI);
// Restart HAL systick
HAL_ResumeTick();
}
#else #else
static TIM_HandleTypeDef TimMasterHandle; static TIM_HandleTypeDef TimMasterHandle;
@ -67,6 +79,21 @@ void sleep(void)
} }
#endif #endif
#if defined(TARGET_STM32F030R8)
void deepsleep(void)
{
// Request to enter STOP mode with regulator in low power mode
HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI);
HAL_InitTick(TICK_INT_PRIORITY);
// After wake-up from STOP reconfigure the PLL
SetSysClock();
HAL_InitTick(TICK_INT_PRIORITY);
}
#else
void deepsleep(void) void deepsleep(void)
{ {
// Request to enter STOP mode with regulator in low power mode // Request to enter STOP mode with regulator in low power mode
@ -75,5 +102,6 @@ void deepsleep(void)
// After wake-up from STOP reconfigure the PLL // After wake-up from STOP reconfigure the PLL
SetSysClock(); SetSysClock();
} }
#endif
#endif #endif

View File

@ -114,6 +114,157 @@ void us_ticker_clear_interrupt(void)
} }
} }
#elif defined(TARGET_STM32F030R8)
// Timer selection:
#define TIM_MST TIM1
#define TIM_MST_UP_IRQ TIM1_BRK_UP_TRG_COM_IRQn
#define TIM_MST_OC_IRQ TIM1_CC_IRQn
#define TIM_MST_RCC __TIM1_CLK_ENABLE()
static TIM_HandleTypeDef TimMasterHandle;
static int us_ticker_inited = 0;
static volatile uint32_t SlaveCounter = 0;
static volatile uint32_t oc_int_part = 0;
static volatile uint16_t oc_rem_part = 0;
void set_compare(uint16_t count)
{
TimMasterHandle.Instance = TIM_MST;
// Set new output compare value
__HAL_TIM_SetCompare(&TimMasterHandle, TIM_CHANNEL_1, count);
// Enable IT
__HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_CC1);
}
// Used to increment the slave counter
static void tim_update_irq_handler(void)
{
TimMasterHandle.Instance = TIM_MST;
// Clear Update interrupt flag
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE);
SlaveCounter++;
}
}
// Used by interrupt system
static void tim_oc_irq_handler(void)
{
uint16_t cval = TIM_MST->CNT;
TimMasterHandle.Instance = TIM_MST;
// Clear CC1 interrupt flag
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1);
}
if (oc_rem_part > 0) {
set_compare(oc_rem_part); // Finish the remaining time left
oc_rem_part = 0;
} else {
if (oc_int_part > 0) {
set_compare(0xFFFF);
oc_rem_part = cval; // To finish the counter loop the next time
oc_int_part--;
} else {
us_ticker_irq_handler();
}
}
}
void us_ticker_init(void)
{
if (us_ticker_inited) return;
us_ticker_inited = 1;
// Enable timer clock
TIM_MST_RCC;
// Configure time base
TimMasterHandle.Instance = TIM_MST;
TimMasterHandle.Init.Period = 0xFFFF;
TimMasterHandle.Init.Prescaler = (uint32_t)(SystemCoreClock / 1000000) - 1; // 1 <20>s tick
TimMasterHandle.Init.ClockDivision = 0;
TimMasterHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
HAL_TIM_Base_Init(&TimMasterHandle);
// Configure interrupts
__HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_UPDATE);
// Update interrupt used for 32-bit counter
NVIC_SetVector(TIM_MST_UP_IRQ, (uint32_t)tim_update_irq_handler);
NVIC_EnableIRQ(TIM_MST_UP_IRQ);
// Output compare interrupt used for timeout feature
NVIC_SetVector(TIM_MST_OC_IRQ, (uint32_t)tim_oc_irq_handler);
NVIC_EnableIRQ(TIM_MST_OC_IRQ);
// Enable timer
HAL_TIM_Base_Start(&TimMasterHandle);
}
uint32_t us_ticker_read()
{
uint32_t counter, counter2;
if (!us_ticker_inited) us_ticker_init();
// A situation might appear when Master overflows right after Slave is read and before the
// new (overflowed) value of Master is read. Which would make the code below consider the
// previous (incorrect) value of Slave and the new value of Master, which would return a
// value in the past. Avoid this by computing consecutive values of the timer until they
// are properly ordered.
counter = (uint32_t)(SlaveCounter << 16);
counter += TIM_MST->CNT;
while (1) {
counter2 = (uint32_t)(SlaveCounter << 16);
counter2 += TIM_MST->CNT;
if (counter2 > counter) {
break;
}
counter = counter2;
}
return counter2;
}
void us_ticker_set_interrupt(timestamp_t timestamp)
{
int delta = (int)((uint32_t)timestamp - us_ticker_read());
uint16_t cval = TIM_MST->CNT;
if (delta <= 0) { // This event was in the past
us_ticker_irq_handler();
} else {
oc_int_part = (uint32_t)(delta >> 16);
oc_rem_part = (uint16_t)(delta & 0xFFFF);
if (oc_rem_part <= (0xFFFF - cval)) {
set_compare(cval + oc_rem_part);
oc_rem_part = 0;
} else {
set_compare(0xFFFF);
oc_rem_part = oc_rem_part - (0xFFFF - cval);
}
}
}
void us_ticker_disable_interrupt(void)
{
TimMasterHandle.Instance = TIM_MST;
__HAL_TIM_DISABLE_IT(&TimMasterHandle, TIM_IT_CC1);
}
void us_ticker_clear_interrupt(void)
{
TimMasterHandle.Instance = TIM_MST;
if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) {
__HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1);
}
}
#else #else
// 32-bit timer selection // 32-bit timer selection