mirror of
https://github.com/RIOT-OS/RIOT.git
synced 2024-12-29 04:50:03 +01:00
Merge pull request #6186 from haukepetersen/opt_stm32_pwm
cpu/stm32x: unified PWM driver implementations
This commit is contained in:
commit
79043d2518
@ -76,24 +76,21 @@ static const timer_conf_t timer_config[] = {
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name PWM configuration
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
#define PWM_NUMOF (1U)
|
||||
#define PWM_0_EN 1
|
||||
#define PWM_MAX_CHANNELS 1 /* Increase if Timer with more channels is used */
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.dev = TIM11,
|
||||
.rcc_mask = RCC_APB2ENR_TIM11EN,
|
||||
.pins = { GPIO_PIN(PORT_B, 9), GPIO_UNDEF, GPIO_UNDEF, GPIO_UNDEF },
|
||||
.af = GPIO_AF3,
|
||||
.chan = 1,
|
||||
.bus = APB2
|
||||
}
|
||||
};
|
||||
|
||||
/* PWM 0 device configuration */
|
||||
#define PWM_0_DEV TIM11
|
||||
#define PWM_0_CHANNELS 1
|
||||
#define PWM_0_CLK (168000000U)
|
||||
#define PWM_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_TIM11EN)
|
||||
#define PWM_0_CLKDIS() (RCC->APB2ENR &= ~RCC_APB2ENR_TIM11EN)
|
||||
/* PWM 0 pin configuration */
|
||||
#define PWM_0_PORT GPIOB
|
||||
#define PWM_0_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
|
||||
#define PWM_0_PIN_CH0 9
|
||||
#define PWM_0_PIN_AF 3
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
@ -51,25 +51,22 @@ extern "C" {
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name PWM configuration
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
#define PWM_NUMOF (1U)
|
||||
#define PWM_0_EN 1
|
||||
|
||||
static const pwm_conf_t pwm_config[PWM_NUMOF] = {
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.tim = 2,
|
||||
.port = GPIOC,
|
||||
.bus = AHB1,
|
||||
.rcc_mask = RCC_AHB1ENR_GPIOCEN,
|
||||
.CH0 = 6,
|
||||
.CH1 = 7,
|
||||
.CH2 = 8,
|
||||
.CH3 = 9,
|
||||
.AF = 2
|
||||
.dev = TIM3,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.pins = { GPIO_PIN(PORT_C, 6), GPIO_PIN(PORT_C, 7),
|
||||
GPIO_PIN(PORT_C, 8), GPIO_PIN(PORT_C, 9) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
}
|
||||
};
|
||||
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
@ -91,13 +88,6 @@ static const timer_conf_t timer_config[] = {
|
||||
.bus = APB1,
|
||||
.irqn = TIM5_IRQn
|
||||
},
|
||||
{
|
||||
.dev = TIM3,
|
||||
.max = 0xffffffff,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.bus = APB1,
|
||||
.irqn = TIM3_IRQn
|
||||
},
|
||||
{
|
||||
.dev = TIM4,
|
||||
.max = 0xffffffff,
|
||||
|
@ -124,28 +124,22 @@ static const timer_conf_t timer_config[] = {
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief PWM configuration
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
#define PWM_NUMOF (1U)
|
||||
#define PWM_0_EN 1
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.dev = TIM3,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.pins = { GPIO_PIN(PORT_C, 6), GPIO_PIN(PORT_C, 7),
|
||||
GPIO_PIN(PORT_C, 8), GPIO_PIN(PORT_C, 9) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
}
|
||||
};
|
||||
|
||||
#define PWM_MAX_CHANNELS 4
|
||||
|
||||
/* PWM 0 device configuration */
|
||||
#define PWM_0_DEV TIM3
|
||||
#define PWM_0_CHANNELS 4
|
||||
#define PWM_0_CLK (72000000U)
|
||||
#define PWM_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM3EN)
|
||||
#define PWM_0_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN))
|
||||
/* PWM 0 pin configuration */
|
||||
#define PWM_0_PORT GPIOC
|
||||
#define PWM_0_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN)
|
||||
#define PWM_0_PIN_CH0 6
|
||||
#define PWM_0_PIN_CH1 7
|
||||
#define PWM_0_PIN_CH2 8
|
||||
#define PWM_0_PIN_CH3 9
|
||||
#define PWM_0_PIN_AF 2
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
@ -1,6 +1,7 @@
|
||||
# Put defined MCU peripherals here (in alphabetical order)
|
||||
FEATURES_PROVIDED += periph_cpuid
|
||||
FEATURES_PROVIDED += periph_gpio
|
||||
FEATURES_PROVIDED += periph_pwm
|
||||
FEATURES_PROVIDED += periph_spi
|
||||
FEATURES_PROVIDED += periph_timer
|
||||
FEATURES_PROVIDED += periph_uart
|
||||
|
@ -101,6 +101,25 @@ static const timer_conf_t timer_config[] = {
|
||||
#define UART_0_AF 7
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.dev = TIM3,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.pins = { GPIO_PIN(PORT_C, 6), GPIO_PIN(PORT_C, 7),
|
||||
GPIO_PIN(PORT_C, 8), GPIO_PIN(PORT_C, 9) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
}
|
||||
};
|
||||
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name SPI configuration
|
||||
* @{
|
||||
|
@ -126,44 +126,31 @@ static const timer_conf_t timer_config[] = {
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @brief PWM configuration
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
#define PWM_NUMOF (2U)
|
||||
#define PWM_0_EN 1
|
||||
#define PWM_1_EN 1
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.dev = TIM3,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.pins = { GPIO_PIN(PORT_C, 6), GPIO_PIN(PORT_C, 7),
|
||||
GPIO_PIN(PORT_C, 8), GPIO_PIN(PORT_C, 9) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
},
|
||||
{
|
||||
.dev = TIM4,
|
||||
.rcc_mask = RCC_APB1ENR_TIM4EN,
|
||||
.pins = { GPIO_PIN(PORT_D, 12), GPIO_PIN(PORT_D, 13),
|
||||
GPIO_PIN(PORT_D, 14), GPIO_PIN(PORT_D, 15) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
}
|
||||
};
|
||||
|
||||
#define PWM_MAX_CHANNELS 4
|
||||
|
||||
/* PWM 0 device configuration */
|
||||
#define PWM_0_DEV TIM3
|
||||
#define PWM_0_CHANNELS 4
|
||||
#define PWM_0_CLK (72000000U)
|
||||
#define PWM_0_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM3EN)
|
||||
#define PWM_0_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN))
|
||||
/* PWM 0 pin configuration */
|
||||
#define PWM_0_PORT GPIOC
|
||||
#define PWM_0_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIOCEN)
|
||||
#define PWM_0_PIN_CH0 6
|
||||
#define PWM_0_PIN_CH1 7
|
||||
#define PWM_0_PIN_CH2 8
|
||||
#define PWM_0_PIN_CH3 9
|
||||
#define PWM_0_PIN_AF 2
|
||||
|
||||
/* PWM 1 device configuration */
|
||||
#define PWM_1_DEV TIM4
|
||||
#define PWM_1_CHANNELS 4
|
||||
#define PWM_1_CLK (72000000U)
|
||||
#define PWM_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM4EN)
|
||||
#define PWM_1_CLKDIS() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN))
|
||||
/* PWM 1 pin configuration */
|
||||
#define PWM_1_PORT GPIOD
|
||||
#define PWM_1_PORT_CLKEN() (RCC->AHBENR |= RCC_AHBENR_GPIODEN)
|
||||
#define PWM_1_PIN_CH0 12
|
||||
#define PWM_1_PIN_CH1 13
|
||||
#define PWM_1_PIN_CH2 14
|
||||
#define PWM_1_PIN_CH3 15
|
||||
#define PWM_1_PIN_AF 2
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
@ -148,43 +148,31 @@ static const uart_conf_t uart_config[] = {
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
* @name PWM configuration
|
||||
* @brief PWM configuration
|
||||
* @{
|
||||
*/
|
||||
#define PWM_NUMOF (2U)
|
||||
#define PWM_0_EN 1
|
||||
#define PWM_1_EN 1
|
||||
#define PWM_MAX_CHANNELS 4
|
||||
static const pwm_conf_t pwm_config[] = {
|
||||
{
|
||||
.dev = TIM1,
|
||||
.rcc_mask = RCC_APB2ENR_TIM1EN,
|
||||
.pins = { GPIO_PIN(PORT_E, 9), GPIO_PIN(PORT_E, 11),
|
||||
GPIO_PIN(PORT_E, 11), GPIO_PIN(PORT_E, 14) },
|
||||
.af = GPIO_AF1,
|
||||
.chan = 4,
|
||||
.bus = APB2
|
||||
},
|
||||
{
|
||||
.dev = TIM3,
|
||||
.rcc_mask = RCC_APB1ENR_TIM3EN,
|
||||
.pins = { GPIO_PIN(PORT_B, 4), GPIO_PIN(PORT_B, 5),
|
||||
GPIO_PIN(PORT_B, 0), GPIO_PIN(PORT_B, 1) },
|
||||
.af = GPIO_AF2,
|
||||
.chan = 4,
|
||||
.bus = APB1
|
||||
}
|
||||
};
|
||||
|
||||
/* PWM 0 device configuration */
|
||||
#define PWM_0_DEV TIM1
|
||||
#define PWM_0_CHANNELS 4
|
||||
#define PWM_0_CLK (168000000U)
|
||||
#define PWM_0_CLKEN() (RCC->APB2ENR |= RCC_APB2ENR_TIM1EN)
|
||||
#define PWM_0_CLKDIS() (RCC->APB2ENR &= ~RCC_APB2ENR_TIM1EN)
|
||||
/* PWM 0 pin configuration */
|
||||
#define PWM_0_PORT GPIOE
|
||||
#define PWM_0_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOEEN)
|
||||
#define PWM_0_PIN_CH0 9
|
||||
#define PWM_0_PIN_CH1 11
|
||||
#define PWM_0_PIN_CH2 13
|
||||
#define PWM_0_PIN_CH3 14
|
||||
#define PWM_0_PIN_AF 1
|
||||
|
||||
/* PWM 1 device configuration */
|
||||
#define PWM_1_DEV TIM3
|
||||
#define PWM_1_CHANNELS 3
|
||||
#define PWM_1_CLK (84000000U)
|
||||
#define PWM_1_CLKEN() (RCC->APB1ENR |= RCC_APB1ENR_TIM3EN)
|
||||
#define PWM_1_CLKDIS() (RCC->APB1ENR &= ~RCC_APB1ENR_TIM3EN)
|
||||
/* PWM 1 pin configuration */
|
||||
#define PWM_1_PORT GPIOB
|
||||
#define PWM_1_PORT_CLKEN() (RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN)
|
||||
#define PWM_1_PIN_CH0 4
|
||||
#define PWM_1_PIN_CH1 5
|
||||
#define PWM_1_PIN_CH2 0
|
||||
#define PWM_1_PIN_CH3 1
|
||||
#define PWM_1_PIN_AF 2
|
||||
#define PWM_NUMOF (sizeof(pwm_config) / sizeof(pwm_config[0]))
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
@ -70,6 +70,30 @@ typedef uint32_t gpio_t;
|
||||
*/
|
||||
#define GPIO_PIN(x, y) ((GPIOA_BASE + (x << 10)) | y)
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
#ifndef CPU_FAM_STM32F0
|
||||
GPIO_AF4, /**< use alternate function 4 */
|
||||
GPIO_AF5, /**< use alternate function 5 */
|
||||
GPIO_AF6, /**< use alternate function 6 */
|
||||
GPIO_AF7, /**< use alternate function 7 */
|
||||
GPIO_AF8, /**< use alternate function 8 */
|
||||
GPIO_AF9, /**< use alternate function 9 */
|
||||
GPIO_AF10, /**< use alternate function 10 */
|
||||
GPIO_AF11, /**< use alternate function 11 */
|
||||
GPIO_AF12, /**< use alternate function 12 */
|
||||
GPIO_AF13, /**< use alternate function 13 */
|
||||
GPIO_AF14, /**< use alternate function 14 */
|
||||
GPIO_AF15 /**< use alternate function 15 */
|
||||
#endif
|
||||
} gpio_af_t;
|
||||
|
||||
/**
|
||||
* @brief Timer configuration
|
||||
*/
|
||||
@ -81,6 +105,18 @@ typedef struct {
|
||||
uint8_t irqn; /**< global IRQ channel */
|
||||
} timer_conf_t;
|
||||
|
||||
/**
|
||||
* @brief PWM configuration
|
||||
*/
|
||||
typedef struct {
|
||||
TIM_TypeDef *dev; /**< Timer used */
|
||||
uint32_t rcc_mask; /**< bit in clock enable register */
|
||||
gpio_t pins[4]; /**< pins used, set to GPIO_UNDEF if not used */
|
||||
gpio_af_t af; /**< alternate function used */
|
||||
uint8_t chan; /**< number of configured channels */
|
||||
uint8_t bus; /**< APB bus */
|
||||
} pwm_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Get the actual bus clock frequency for the APB buses
|
||||
*
|
||||
|
142
cpu/stm32_common/periph/pwm.c
Normal file
142
cpu/stm32_common/periph/pwm.c
Normal file
@ -0,0 +1,142 @@
|
||||
/*
|
||||
* Copyright (C) 2014-2016 Freie Universität Berlin
|
||||
* 2015 Engineering-Spirit
|
||||
* 2016 OTA keys S.A.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32_common
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level PWM driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Fabian Nack <nack@inf.fu-berlin.de>
|
||||
* @author Nick v. IJzendoorn <nijzendoorn@engineering-spirit.nl>
|
||||
* @author Aurelien Gonce <aurelien.gonce@altran.fr>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "assert.h"
|
||||
#include "periph/pwm.h"
|
||||
#include "periph/gpio.h"
|
||||
|
||||
#ifdef PWM_NUMOF
|
||||
|
||||
#define CCMR_LEFT (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 | \
|
||||
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2)
|
||||
#define CCMR_RIGHT (TIM_CCMR1_OC1M_0 | TIM_CCMR1_OC1M_1 | \
|
||||
TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC2M_0 | \
|
||||
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
|
||||
|
||||
static inline TIM_TypeDef *dev(pwm_t pwm)
|
||||
{
|
||||
return pwm_config[pwm].dev;
|
||||
}
|
||||
|
||||
uint32_t pwm_init(pwm_t pwm, pwm_mode_t mode, uint32_t freq, uint16_t res)
|
||||
{
|
||||
uint32_t bus_clk = periph_apb_clk(pwm_config[pwm].bus);
|
||||
|
||||
/* verify parameters */
|
||||
assert((pwm < PWM_NUMOF) && ((freq * res) < bus_clk));
|
||||
|
||||
/* power on the used timer */
|
||||
pwm_poweron(pwm);
|
||||
/* reset configuration and CC channels */
|
||||
dev(pwm)->CR1 = 0;
|
||||
dev(pwm)->CR2 = 0;
|
||||
for (int i = 0; i < TIMER_CHAN; i++) {
|
||||
dev(pwm)->CCR[i] = 0;
|
||||
}
|
||||
|
||||
/* configure the used pins */
|
||||
for (unsigned i = 0; i < pwm_config[pwm].chan; i++) {
|
||||
gpio_init(pwm_config[pwm].pins[i], GPIO_OUT);
|
||||
gpio_init_af(pwm_config[pwm].pins[i], pwm_config[pwm].af);
|
||||
}
|
||||
|
||||
/* configure the PWM frequency and resolution by setting the auto-reload
|
||||
* and prescaler registers */
|
||||
dev(pwm)->PSC = (bus_clk / (res * freq)) - 1;
|
||||
dev(pwm)->ARR = res - 1;
|
||||
|
||||
/* set PWM mode */
|
||||
switch (mode) {
|
||||
case PWM_LEFT:
|
||||
dev(pwm)->CCMR1 = CCMR_LEFT;
|
||||
dev(pwm)->CCMR2 = CCMR_LEFT;
|
||||
break;
|
||||
case PWM_RIGHT:
|
||||
dev(pwm)->CCMR1 = CCMR_RIGHT;
|
||||
dev(pwm)->CCMR2 = CCMR_RIGHT;
|
||||
break;
|
||||
case PWM_CENTER:
|
||||
dev(pwm)->CCMR1 = 0;
|
||||
dev(pwm)->CCMR2 = 0;
|
||||
dev(pwm)->CR1 |= (TIM_CR1_CMS_0 | TIM_CR1_CMS_1);
|
||||
break;
|
||||
}
|
||||
|
||||
/* enable PWM outputs and start PWM generation */
|
||||
#ifdef TIM_BDTR_MOE
|
||||
dev(pwm)->BDTR = TIM_BDTR_MOE;
|
||||
#endif
|
||||
dev(pwm)->CCER = (TIM_CCER_CC1E | TIM_CCER_CC2E |
|
||||
TIM_CCER_CC3E | TIM_CCER_CC4E);
|
||||
dev(pwm)->CR1 |= TIM_CR1_CEN;
|
||||
|
||||
/* return the actual used PWM frequency */
|
||||
return (bus_clk / (res * (dev(pwm)->PSC + 1)));
|
||||
}
|
||||
|
||||
uint8_t pwm_channels(pwm_t pwm)
|
||||
{
|
||||
assert(pwm < PWM_NUMOF);
|
||||
return pwm_config[pwm].chan;
|
||||
}
|
||||
|
||||
void pwm_set(pwm_t pwm, uint8_t channel, uint16_t value)
|
||||
{
|
||||
assert((pwm < PWM_NUMOF) && (channel < pwm_config[pwm].chan));
|
||||
|
||||
/* norm value to maximum possible value */
|
||||
if (value > dev(pwm)->ARR) {
|
||||
value = (uint16_t)dev(pwm)->ARR;
|
||||
}
|
||||
/* set new value */
|
||||
dev(pwm)->CCR[channel] = value;
|
||||
}
|
||||
|
||||
void pwm_start(pwm_t pwm)
|
||||
{
|
||||
assert(pwm < PWM_NUMOF);
|
||||
dev(pwm)->CR1 |= TIM_CR1_CEN;
|
||||
}
|
||||
|
||||
void pwm_stop(pwm_t pwm)
|
||||
{
|
||||
assert(pwm < PWM_NUMOF);
|
||||
dev(pwm)->CR1 &= ~TIM_CR1_CEN;
|
||||
}
|
||||
|
||||
void pwm_poweron(pwm_t pwm)
|
||||
{
|
||||
assert(pwm < PWM_NUMOF);
|
||||
periph_clk_en(pwm_config[pwm].bus, pwm_config[pwm].rcc_mask);
|
||||
}
|
||||
|
||||
void pwm_poweroff(pwm_t pwm)
|
||||
{
|
||||
assert(pwm < PWM_NUMOF);
|
||||
periph_clk_dis(pwm_config[pwm].bus, pwm_config[pwm].rcc_mask);
|
||||
}
|
||||
|
||||
#endif /* PWM_NUMOF */
|
@ -75,16 +75,6 @@ enum {
|
||||
PORT_F = 5, /**< port F */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
} gpio_af_t;
|
||||
|
||||
#ifndef DOXYGEN
|
||||
/**
|
||||
* @brief Override ADC resolution values
|
||||
|
@ -76,43 +76,6 @@ enum {
|
||||
PORT_I = 8 /**< port I */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
GPIO_AF4, /**< use alternate function 4 */
|
||||
GPIO_AF5, /**< use alternate function 5 */
|
||||
GPIO_AF6, /**< use alternate function 6 */
|
||||
GPIO_AF7, /**< use alternate function 7 */
|
||||
GPIO_AF8, /**< use alternate function 8 */
|
||||
GPIO_AF9, /**< use alternate function 9 */
|
||||
GPIO_AF10, /**< use alternate function 10 */
|
||||
GPIO_AF11, /**< use alternate function 11 */
|
||||
GPIO_AF12, /**< use alternate function 12 */
|
||||
GPIO_AF13, /**< use alternate function 13 */
|
||||
GPIO_AF14 /**< use alternate function 14 */
|
||||
} gpio_af_t;
|
||||
|
||||
/**
|
||||
* @name PWM configuration
|
||||
* @{
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t tim; /**< timer used */
|
||||
GPIO_TypeDef *port; /**< pwm device */
|
||||
uint8_t bus; /**< AHBx bus */
|
||||
uint32_t rcc_mask; /**< corresponding bit in the RCC register */
|
||||
uint8_t CH0; /**< channel 0 */
|
||||
uint8_t CH1; /**< channel 1 */
|
||||
uint8_t CH2; /**< channel 2 */
|
||||
uint8_t CH3; /**< channel 3 */
|
||||
uint8_t AF; /**< alternate function */
|
||||
} pwm_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Structure for UART configuration data
|
||||
* @{
|
||||
|
@ -64,29 +64,6 @@ enum {
|
||||
PORT_F = 5, /**< port F */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*
|
||||
* For some reason AF13 is not used on this CPU.
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
GPIO_AF4, /**< use alternate function 4 */
|
||||
GPIO_AF5, /**< use alternate function 5 */
|
||||
GPIO_AF6, /**< use alternate function 6 */
|
||||
GPIO_AF7, /**< use alternate function 7 */
|
||||
GPIO_AF8, /**< use alternate function 8 */
|
||||
GPIO_AF9, /**< use alternate function 9 */
|
||||
GPIO_AF10, /**< use alternate function 10 */
|
||||
GPIO_AF11, /**< use alternate function 11 */
|
||||
GPIO_AF12, /**< use alternate function 12 */
|
||||
GPIO_AF14, /**< use alternate function 14 */
|
||||
GPIO_AF15 /**< use alternate function 14 */
|
||||
} gpio_af_t;
|
||||
|
||||
/**
|
||||
* @brief DAC line configuration support
|
||||
*/
|
||||
@ -96,6 +73,16 @@ typedef struct {
|
||||
uint8_t chan; /**< DAC device used for this line */
|
||||
} dac_conf_t;
|
||||
|
||||
/**
|
||||
* @brief Configure the alternate function for the given pin
|
||||
*
|
||||
* @note This is meant for internal use in STM32F4 peripheral drivers only
|
||||
*
|
||||
* @param[in] pin pin to configure
|
||||
* @param[in] af alternate function to use
|
||||
*/
|
||||
void gpio_init_af(gpio_t pin, gpio_af_t af);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
@ -1,237 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f3
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level PWM driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
/* guard file in case no PWM device is defined */
|
||||
#if (PWM_0_EN || PWM_1_EN)
|
||||
|
||||
/* pull the PWM header inside the guards for now. Guards will be removed on
|
||||
* adapting this driver implementation... */
|
||||
#include "periph/pwm.h"
|
||||
|
||||
uint32_t pwm_init(pwm_t dev, pwm_mode_t mode, uint32_t freq, uint16_t res)
|
||||
{
|
||||
TIM_TypeDef *tim = NULL;
|
||||
GPIO_TypeDef *port = NULL;
|
||||
uint32_t pins[PWM_MAX_CHANNELS];
|
||||
uint32_t af;
|
||||
int channels;
|
||||
uint32_t pwm_clk;
|
||||
|
||||
pwm_poweron(dev);
|
||||
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
tim = PWM_0_DEV;
|
||||
port = PWM_0_PORT;
|
||||
pins[0] = PWM_0_PIN_CH0;
|
||||
pins[1] = PWM_0_PIN_CH1;
|
||||
pins[2] = PWM_0_PIN_CH2;
|
||||
pins[3] = PWM_0_PIN_CH3;
|
||||
af = PWM_0_PIN_AF;
|
||||
channels = PWM_0_CHANNELS;
|
||||
pwm_clk = PWM_0_CLK;
|
||||
PWM_0_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
tim = PWM_1_DEV;
|
||||
port = PWM_1_PORT;
|
||||
pins[0] = PWM_1_PIN_CH0;
|
||||
pins[1] = PWM_1_PIN_CH1;
|
||||
pins[2] = PWM_1_PIN_CH2;
|
||||
pins[3] = PWM_1_PIN_CH3;
|
||||
af = PWM_1_PIN_AF;
|
||||
channels = PWM_1_CHANNELS;
|
||||
pwm_clk = PWM_1_CLK;
|
||||
PWM_1_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
pwm_poweroff(dev);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* setup pins: alternate function */
|
||||
for (int i = 0; i < channels; i++) {
|
||||
port->MODER &= ~(3 << (pins[i] * 2));
|
||||
port->MODER |= (2 << (pins[i] * 2));
|
||||
if (pins[i] < 8) {
|
||||
port->AFR[0] &= ~(0xf << (pins[i] * 4));
|
||||
port->AFR[0] |= (af << (pins[i] * 4));
|
||||
}
|
||||
else {
|
||||
port->AFR[1] &= ~(0xf << ((pins[i] - 8) * 4));
|
||||
port->AFR[1] |= (af << ((pins[i] - 8) * 4));
|
||||
}
|
||||
}
|
||||
|
||||
/* reset timer configuration registers */
|
||||
tim->CR1 = 0;
|
||||
tim->CR2 = 0;
|
||||
tim->CCMR1 = 0;
|
||||
tim->CCMR2 = 0;
|
||||
|
||||
/* set prescale and auto-reload registers to matching values for resolution and frequency */
|
||||
if ((res > 0xffff) || ((res * freq) > pwm_clk)) {
|
||||
return 0;
|
||||
}
|
||||
tim->PSC = (pwm_clk / (res * freq)) - 1;
|
||||
tim->ARR = res - 1;
|
||||
freq = (pwm_clk / (res * (tim->PSC + 1)));
|
||||
|
||||
/* set PWM mode */
|
||||
switch (mode) {
|
||||
case PWM_LEFT:
|
||||
tim->CCMR1 |= (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
|
||||
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
|
||||
tim->CCMR2 |= (TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
|
||||
TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
|
||||
break;
|
||||
case PWM_RIGHT:
|
||||
tim->CCMR1 |= (TIM_CCMR1_OC1M_0 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
|
||||
TIM_CCMR1_OC2M_0 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
|
||||
tim->CCMR2 |= (TIM_CCMR2_OC3M_0 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
|
||||
TIM_CCMR2_OC4M_0 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
|
||||
break;
|
||||
case PWM_CENTER:
|
||||
tim->CR1 |= (TIM_CR1_CMS_0 | TIM_CR1_CMS_1);
|
||||
break;
|
||||
}
|
||||
|
||||
/* enable output on PWM pins */
|
||||
tim->CCER |= (TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E);
|
||||
|
||||
/* enable PWM generation */
|
||||
pwm_start(dev);
|
||||
|
||||
return freq;
|
||||
}
|
||||
|
||||
uint8_t pwm_channels(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
return PWM_0_CHANNELS;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
return PWM_1_CHANNELS;
|
||||
#endif
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_set(pwm_t dev, uint8_t channel, uint16_t value)
|
||||
{
|
||||
TIM_TypeDef *tim = NULL;
|
||||
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
tim = PWM_0_DEV;
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
tim = PWM_1_DEV;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
tim->CCR[channel] = value;
|
||||
}
|
||||
|
||||
void pwm_start(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_stop(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_DEV->CR1 &= ~(TIM_CR1_CEN);
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_DEV->CR1 &= ~(TIM_CR1_CEN);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_poweron(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_poweroff(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_CLKDIS();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_CLKDIS();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* (PWM_0_EN || PWM_1_EN) */
|
@ -102,27 +102,6 @@ enum {
|
||||
PORT_I = 8 /**< port I */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
GPIO_AF4, /**< use alternate function 4 */
|
||||
GPIO_AF5, /**< use alternate function 5 */
|
||||
GPIO_AF6, /**< use alternate function 6 */
|
||||
GPIO_AF7, /**< use alternate function 7 */
|
||||
GPIO_AF8, /**< use alternate function 8 */
|
||||
GPIO_AF9, /**< use alternate function 9 */
|
||||
GPIO_AF10, /**< use alternate function 10 */
|
||||
GPIO_AF11, /**< use alternate function 11 */
|
||||
GPIO_AF12, /**< use alternate function 12 */
|
||||
GPIO_AF13, /**< use alternate function 13 */
|
||||
GPIO_AF14 /**< use alternate function 14 */
|
||||
} gpio_af_t;
|
||||
|
||||
/**
|
||||
* @brief Structure for UART configuration data
|
||||
* @{
|
||||
|
@ -1,281 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freie Universität Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_stm32f4
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level PWM driver implementation
|
||||
*
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
* @author Fabian Nack <nack@inf.fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph_conf.h"
|
||||
|
||||
/* guard file in case no PWM device is defined */
|
||||
#if (PWM_0_EN || PWM_1_EN)
|
||||
|
||||
/* pull the PWM header inside the guards for now. Guards will be removed on
|
||||
* adapting this driver implementation... */
|
||||
#include "periph/pwm.h"
|
||||
|
||||
uint32_t pwm_init(pwm_t dev, pwm_mode_t mode, uint32_t freq, uint16_t res)
|
||||
{
|
||||
TIM_TypeDef *tim = NULL;
|
||||
GPIO_TypeDef *port = NULL;
|
||||
uint32_t pins[PWM_MAX_CHANNELS];
|
||||
uint32_t af = 0;
|
||||
uint32_t pwm_clk = 0;
|
||||
int channels = 0;
|
||||
|
||||
pwm_poweron(dev);
|
||||
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
tim = PWM_0_DEV;
|
||||
port = PWM_0_PORT;
|
||||
pins[0] = PWM_0_PIN_CH0;
|
||||
#if (PWM_0_CHANNELS > 1)
|
||||
pins[1] = PWM_0_PIN_CH1;
|
||||
#endif
|
||||
#if (PWM_0_CHANNELS > 2)
|
||||
pins[2] = PWM_0_PIN_CH2;
|
||||
#endif
|
||||
#if (PWM_0_CHANNELS > 3)
|
||||
pins[3] = PWM_0_PIN_CH3;
|
||||
#endif
|
||||
af = PWM_0_PIN_AF;
|
||||
channels = PWM_0_CHANNELS;
|
||||
pwm_clk = PWM_0_CLK;
|
||||
PWM_0_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
tim = PWM_1_DEV;
|
||||
port = PWM_1_PORT;
|
||||
pins[0] = PWM_1_PIN_CH0;
|
||||
#if (PWM_1_CHANNELS > 1)
|
||||
pins[1] = PWM_1_PIN_CH1;
|
||||
#endif
|
||||
#if (PWM_1_CHANNELS > 2)
|
||||
pins[2] = PWM_1_PIN_CH2;
|
||||
#endif
|
||||
#if (PWM_1_CHANNELS > 3)
|
||||
pins[3] = PWM_1_PIN_CH3;
|
||||
#endif
|
||||
af = PWM_1_PIN_AF;
|
||||
channels = PWM_1_CHANNELS;
|
||||
pwm_clk = PWM_1_CLK;
|
||||
PWM_1_PORT_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* setup pins: alternate function */
|
||||
for (int i = 0; i < channels; i++) {
|
||||
port->MODER &= ~(3 << (pins[i] * 2));
|
||||
port->MODER |= (2 << (pins[i] * 2));
|
||||
if (pins[i] < 8) {
|
||||
port->AFR[0] &= ~(0xf << (pins[i] * 4));
|
||||
port->AFR[0] |= (af << (pins[i] * 4));
|
||||
} else {
|
||||
port->AFR[1] &= ~(0xf << ((pins[i] - 8) * 4));
|
||||
port->AFR[1] |= (af << ((pins[i] - 8) * 4));
|
||||
}
|
||||
}
|
||||
|
||||
/* Reset C/C and timer configuration register */
|
||||
switch (channels) {
|
||||
case 4:
|
||||
tim->CCR[3] = 0;
|
||||
/* Fall through */
|
||||
case 3:
|
||||
tim->CCR[2] = 0;
|
||||
tim->CR2 = 0;
|
||||
/* Fall through */
|
||||
case 2:
|
||||
tim->CCR[1] = 0;
|
||||
/* Fall through */
|
||||
case 1:
|
||||
tim->CCR[0] = 0;
|
||||
tim->CR1 = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
/* set prescale and auto-reload registers to matching values for resolution
|
||||
* and frequency */
|
||||
if (res > 0xffff || (res * freq) > pwm_clk) {
|
||||
return 0;
|
||||
}
|
||||
tim->PSC = (pwm_clk / (res * freq)) - 1;
|
||||
tim->ARR = res - 1;
|
||||
|
||||
/* calculate the actual PWM frequency */
|
||||
freq = (pwm_clk / (res * (tim->PSC + 1)));
|
||||
|
||||
/* set PWM mode */
|
||||
switch (mode) {
|
||||
case PWM_LEFT:
|
||||
tim->CCMR1 = (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
|
||||
TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
|
||||
if (channels > 2) {
|
||||
tim->CCMR2 = (TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
|
||||
TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
|
||||
}
|
||||
break;
|
||||
case PWM_RIGHT:
|
||||
tim->CCMR1 = (TIM_CCMR1_OC1M_0 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 |
|
||||
TIM_CCMR1_OC2M_0 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2);
|
||||
if (channels > 2) {
|
||||
tim->CCMR2 = (TIM_CCMR2_OC3M_0 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 |
|
||||
TIM_CCMR2_OC4M_0 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2);
|
||||
}
|
||||
break;
|
||||
case PWM_CENTER:
|
||||
tim->CCMR1 = 0;
|
||||
if (channels > 2) {
|
||||
tim->CCMR2 = 0;
|
||||
}
|
||||
tim->CR1 |= (TIM_CR1_CMS_0 | TIM_CR1_CMS_1);
|
||||
break;
|
||||
}
|
||||
|
||||
/* enable output on PWM pins */
|
||||
tim->CCER = (TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E);
|
||||
|
||||
/* enable PWM outputs */
|
||||
tim->BDTR = TIM_BDTR_MOE;
|
||||
|
||||
/* enable timer ergo the PWM generation */
|
||||
pwm_start(dev);
|
||||
|
||||
return freq;
|
||||
}
|
||||
|
||||
uint8_t pwm_channels(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
return PWM_0_CHANNELS;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
return PWM_1_CHANNELS;
|
||||
#endif
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_set(pwm_t dev, uint8_t channel, uint16_t value)
|
||||
{
|
||||
TIM_TypeDef *tim = NULL;
|
||||
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
tim = PWM_0_DEV;
|
||||
if (channel >= PWM_0_CHANNELS) {
|
||||
return;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
tim = PWM_1_DEV;
|
||||
if (channel >= PWM_1_CHANNELS) {
|
||||
return;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* norm value to maximum possible value */
|
||||
if (value > tim->ARR) {
|
||||
value = (uint32_t)tim->ARR;
|
||||
}
|
||||
|
||||
tim->CCR[channel] = value;
|
||||
}
|
||||
|
||||
void pwm_start(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_DEV->CR1 |= TIM_CR1_CEN;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_stop(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_DEV->CR1 &= ~(TIM_CR1_CEN);
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_DEV->CR1 &= ~(TIM_CR1_CEN);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_poweron(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_CLKEN();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwm_poweroff(pwm_t dev)
|
||||
{
|
||||
switch (dev) {
|
||||
#if PWM_0_EN
|
||||
case PWM_0:
|
||||
PWM_0_CLKDIS();
|
||||
break;
|
||||
#endif
|
||||
#if PWM_1_EN
|
||||
case PWM_1:
|
||||
PWM_1_CLKDIS();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* (PWM_0_EN || PWM_1_EN) */
|
@ -68,27 +68,6 @@ enum {
|
||||
PORT_H = 5, /**< port H */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Available MUX values for configuring a pin's alternate function
|
||||
*/
|
||||
typedef enum {
|
||||
GPIO_AF0 = 0, /**< use alternate function 0 */
|
||||
GPIO_AF1, /**< use alternate function 1 */
|
||||
GPIO_AF2, /**< use alternate function 2 */
|
||||
GPIO_AF3, /**< use alternate function 3 */
|
||||
GPIO_AF4, /**< use alternate function 4 */
|
||||
GPIO_AF5, /**< use alternate function 5 */
|
||||
GPIO_AF6, /**< use alternate function 6 */
|
||||
GPIO_AF7, /**< use alternate function 7 */
|
||||
GPIO_AF8, /**< use alternate function 8 */
|
||||
GPIO_AF9, /**< use alternate function 9 */
|
||||
GPIO_AF10, /**< use alternate function 10 */
|
||||
GPIO_AF11, /**< use alternate function 11 */
|
||||
GPIO_AF12, /**< use alternate function 12 */
|
||||
GPIO_AF13, /**< use alternate function 13 */
|
||||
GPIO_AF14 /**< use alternate function 14 */
|
||||
} gpio_af_t;
|
||||
|
||||
/**
|
||||
* @brief DAC line configuration data
|
||||
*/
|
||||
|
@ -33,13 +33,6 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Make sure the number of available PWM devices is defined
|
||||
*/
|
||||
#ifndef PWM_NUMOF
|
||||
#error "PWM_NUMOF undefined for the target platform"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Default PWM access macro
|
||||
* @{
|
||||
|
@ -30,7 +30,7 @@
|
||||
#include "periph/pwm.h"
|
||||
#include "servo.h"
|
||||
|
||||
#define DEV PWM_0
|
||||
#define DEV PWM_DEV(0)
|
||||
#define CHANNEL 0
|
||||
|
||||
#define SERVO_MIN (1000U)
|
||||
|
Loading…
Reference in New Issue
Block a user