diff --git a/source/Core/BSP/Magic/IRQ.cpp b/source/Core/BSP/Magic/IRQ.cpp
index 2058599a..b478650b 100644
--- a/source/Core/BSP/Magic/IRQ.cpp
+++ b/source/Core/BSP/Magic/IRQ.cpp
@@ -18,7 +18,6 @@ extern "C" {
#include "bl702_timer.h"
#include "hal_adc.h"
#include "hal_clock.h"
-#include "hal_pwm.h"
#include "hal_timer.h"
}
diff --git a/source/Core/BSP/Magic/Pins.h b/source/Core/BSP/Magic/Pins.h
index 39f29ba5..65dc38fc 100644
--- a/source/Core/BSP/Magic/Pins.h
+++ b/source/Core/BSP/Magic/Pins.h
@@ -21,10 +21,11 @@
#define OLED_RESET_Pin GPIO_PIN_3
#define KEY_A_Pin GPIO_PIN_28
#define PWM_Out_Pin GPIO_PIN_21
+#define PWM_Channel PWM_CH1
#define SCL_Pin GPIO_PIN_11
#define SDA_Pin GPIO_PIN_10
-// #define USB_DM_Pin GPIO_PIN_8
+#define USB_DM_Pin GPIO_PIN_8
#define QC_DP_LOW_Pin GPIO_PIN_5
// LOW = low resistance, HIGH = high resistance
diff --git a/source/Core/BSP/Magic/Setup.cpp b/source/Core/BSP/Magic/Setup.cpp
index 2675d9cd..6221eb63 100644
--- a/source/Core/BSP/Magic/Setup.cpp
+++ b/source/Core/BSP/Magic/Setup.cpp
@@ -19,17 +19,38 @@ uint16_t ADCReadings[ADC_NORM_SAMPLES]; // room for 32 lots of the pair of readi
// Functions
-void setup_slow_PWM();
+void setup_timer_scheduler(void);
+void setup_pwm(void);
void setup_adc(void);
void hardware_init() {
gpio_set_mode(OLED_RESET_Pin, GPIO_OUTPUT_MODE);
gpio_set_mode(KEY_A_Pin, GPIO_INPUT_PD_MODE);
gpio_set_mode(KEY_B_Pin, GPIO_INPUT_PD_MODE);
- setup_slow_PWM();
- setup_adc();
- I2C_ClockSet(I2C0_ID, 400000);
-}
+ setup_timer_scheduler();
+ setup_adc();
+ setup_pwm();
+ I2C_ClockSet(I2C0_ID, 400000); // Sets clock to around 375kHz
+}
+void setup_pwm(void) {
+ // Setup PWM we use for driving the tip
+ PWM_CH_CFG_Type cfg = {
+ PWM_Channel, // channel
+ PWM_CLK_XCLK, // Clock
+ PWM_STOP_GRACEFUL, // Stop mode
+ PWM_POL_NORMAL, // Normal Polarity
+ 50, // Clock Div
+ 100, // Period
+ 0, // Thres 1 - start at beginng
+ 50, // Thres 2 - turn off at 50%
+ 0, // Interrupt pulse count
+ };
+
+ BL_Err_Type err = PWM_Channel_Init(&cfg);
+ uint32_t pwm_clk = peripheral_clock_get(PERIPHERAL_CLOCK_PWM);
+ MSG((char *)"PWM Setup returns %d %d\r\n", err, pwm_clk);
+ PWM_Channel_Enable(PWM_Channel);
+}
void setup_adc(void) {
MSG((char *)"Setting up ADC\r\n");
//
@@ -73,7 +94,7 @@ void setup_adc(void) {
struct device *timer0;
-void setup_slow_PWM() {
+void setup_timer_scheduler() {
timer_register(TIMER0_INDEX, "timer0");
@@ -98,18 +119,11 @@ void setup_slow_PWM() {
}
void setupFUSBIRQ() {
- return; // TODO
- MSG((char *)"Setting up FUSB IRQ\r\n");
gpio_set_mode(FUSB302_IRQ_Pin, GPIO_SYNC_FALLING_TRIGER_INT_MODE);
- MSG((char *)"Setting up FUSB IRQ1r\n");
CPU_Interrupt_Disable(GPIO_INT0_IRQn);
- MSG((char *)"Setting up FUSB IRQ2\r\n");
Interrupt_Handler_Register(GPIO_INT0_IRQn, GPIO_IRQHandler);
- MSG((char *)"Setting up FUSB IRQ3\r\n");
CPU_Interrupt_Enable(GPIO_INT0_IRQn);
-
- MSG((char *)"Setting up FUSB IRQ4\r\n");
gpio_irq_enable(FUSB302_IRQ_Pin, ENABLE);
}
diff --git a/source/Core/BSP/Magic/Setup.h b/source/Core/BSP/Magic/Setup.h
index 275b8a81..1e39d99f 100644
--- a/source/Core/BSP/Magic/Setup.h
+++ b/source/Core/BSP/Magic/Setup.h
@@ -18,9 +18,7 @@ extern "C" {
#include "bl702_timer.h"
#include "hal_adc.h"
#include "hal_clock.h"
-#include "hal_pwm.h"
#include "hal_timer.h"
-
}
#ifdef __cplusplus
extern "C" {
diff --git a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/inc/hal_pwm.h b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/inc/hal_pwm.h
deleted file mode 100644
index f89ca00b..00000000
--- a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/inc/hal_pwm.h
+++ /dev/null
@@ -1,90 +0,0 @@
-/**
- * @file hal_pwm.h
- * @brief
- *
- * Copyright (c) 2021 Bouffalolab team
- *
- * Licensed to the Apache Software Foundation (ASF) under one or more
- * contributor license agreements. See the NOTICE file distributed with
- * this work for additional information regarding copyright ownership. The
- * ASF licenses this file to you under the Apache License, Version 2.0 (the
- * "License"); you may not use this file except in compliance with the
- * License. You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations
- * under the License.
- *
- */
-#ifndef __HAL_PWM__H__
-#define __HAL_PWM__H__
-
-#ifdef __cplusplus
-extern "C"{
-#endif
-
-#include "hal_common.h"
-#include "drv_device.h"
-#include "bl702_config.h"
-
-#define DEVICE_CTRL_PWM_FREQUENCE_CONFIG 0x10
-#define DEVICE_CTRL_PWM_DUTYCYCLE_CONFIG 0x11
-#define DEVICE_CTRL_PWM_IT_PULSE_COUNT_CONFIG 0x12
-
-enum pwm_index_type {
-#ifdef BSP_USING_PWM_CH0
- PWM_CH0_INDEX,
-#endif
-#ifdef BSP_USING_PWM_CH1
- PWM_CH1_INDEX,
-#endif
-#ifdef BSP_USING_PWM_CH2
- PWM_CH2_INDEX,
-#endif
-#ifdef BSP_USING_PWM_CH3
- PWM_CH3_INDEX,
-#endif
-#ifdef BSP_USING_PWM_CH4
- PWM_CH4_INDEX,
-#endif
- PWM_MAX_INDEX
-};
-
-#define pwm_channel_start(dev) device_control(dev, DEVICE_CTRL_RESUME, NULL)
-#define pwm_channel_stop(dev) device_control(dev, DEVICE_CTRL_SUSPEND, NULL)
-#define pwm_channel_freq_update(dev, count) device_control(dev, DEVICE_CTRL_PWM_FREQUENCE_CONFIG, (void *)count)
-#define pwm_channel_dutycycle_update(dev, cfg) device_control(dev, DEVICE_CTRL_PWM_DUTYCYCLE_CONFIG, cfg)
-#define pwm_it_pulse_count_update(dev, count) device_control(dev, DEVICE_CTRL_PWM_IT_PULSE_COUNT_CONFIG, (void *)count)
-
-enum pwm_event_type {
- PWM_EVENT_COMPLETE,
-};
-
-typedef struct
-{
- uint16_t threshold_low;
- uint16_t threshold_high;
-} pwm_dutycycle_config_t;
-
-typedef struct pwm_device {
- struct device parent;
- uint8_t ch;
- uint8_t polarity_invert_mode;
- uint16_t period;
- uint16_t threshold_low;
- uint16_t threshold_high;
- uint16_t it_pulse_count;
-
-} pwm_device_t;
-
-#define PWM_DEV(dev) ((pwm_device_t *)dev)
-
-int pwm_register(enum pwm_index_type index, const char *name);
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_gpio.c b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_gpio.c
index 08fee02f..de878e5e 100644
--- a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_gpio.c
+++ b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_gpio.c
@@ -20,16 +20,16 @@
* under the License.
*
*/
+#include "hal_gpio.h"
#include "bl702_glb.h"
#include "bl702_gpio.h"
-#include "hal_gpio.h"
static void GPIO_IRQ(void);
struct gpio_int_cfg_private {
- slist_t list;
- uint32_t pin;
- void (*cbfun)(uint32_t pin);
+ slist_t list;
+ uint32_t pin;
+ void (*cbfun)(uint32_t pin);
};
static slist_t gpio_int_head = SLIST_OBJECT_INIT(gpio_int_head);
@@ -40,101 +40,100 @@ static slist_t gpio_int_head = SLIST_OBJECT_INIT(gpio_int_head);
* @param pin
* @param mode
*/
-void gpio_set_mode(uint32_t pin, uint32_t mode)
-{
- GLB_GPIO_Cfg_Type gpio_cfg;
+void gpio_set_mode(uint32_t pin, uint32_t mode) {
+ GLB_GPIO_Cfg_Type gpio_cfg;
- gpio_cfg.gpioFun = GPIO_FUN_GPIO;
- gpio_cfg.gpioPin = pin;
- gpio_cfg.drive = 0;
- gpio_cfg.smtCtrl = 1;
+ gpio_cfg.gpioFun = GPIO_FUN_GPIO;
+ gpio_cfg.gpioPin = pin;
+ gpio_cfg.drive = 3;
+ gpio_cfg.smtCtrl = 1;
- switch (mode) {
- case GPIO_OUTPUT_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
- gpio_cfg.pullType = GPIO_PULL_NONE;
- break;
+ switch (mode) {
+ case GPIO_OUTPUT_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
+ gpio_cfg.pullType = GPIO_PULL_NONE;
+ break;
- case GPIO_OUTPUT_PP_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
- gpio_cfg.pullType = GPIO_PULL_UP;
- break;
+ case GPIO_OUTPUT_PP_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ break;
- case GPIO_OUTPUT_PD_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- break;
+ case GPIO_OUTPUT_PD_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_OUTPUT;
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ break;
- case GPIO_INPUT_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_INPUT;
- gpio_cfg.pullType = GPIO_PULL_NONE;
- break;
+ case GPIO_INPUT_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_INPUT;
+ gpio_cfg.pullType = GPIO_PULL_NONE;
+ break;
- case GPIO_INPUT_PP_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_INPUT;
- gpio_cfg.pullType = GPIO_PULL_UP;
- break;
+ case GPIO_INPUT_PP_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_INPUT;
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ break;
- case GPIO_INPUT_PD_MODE:
- gpio_cfg.gpioMode = GPIO_MODE_INPUT;
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- break;
- case GPIO_HZ_MODE:
- GLB_GPIO_Set_HZ(pin);
- default:
- CPU_Interrupt_Disable(GPIO_INT0_IRQn);
- GLB_GPIO_IntMask(pin, MASK);
+ case GPIO_INPUT_PD_MODE:
+ gpio_cfg.gpioMode = GPIO_MODE_INPUT;
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ break;
+ case GPIO_HZ_MODE:
+ GLB_GPIO_Set_HZ(pin);
+ default:
+ CPU_Interrupt_Disable(GPIO_INT0_IRQn);
+ GLB_GPIO_IntMask(pin, MASK);
- gpio_cfg.gpioMode = GPIO_MODE_INPUT;
+ gpio_cfg.gpioMode = GPIO_MODE_INPUT;
- if (mode == GPIO_ASYNC_RISING_TRIGER_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_POS_PULSE);
- }
-
- else if (mode == GPIO_ASYNC_FALLING_TRIGER_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_UP;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_NEG_PULSE);
- }
-
- else if (mode == GPIO_ASYNC_HIGH_LEVEL_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_POS_LEVEL);
- }
-
- else if (mode == GPIO_ASYNC_LOW_LEVEL_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_UP;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_NEG_LEVEL);
- }
-
- else if (mode == GPIO_SYNC_RISING_TRIGER_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_POS_PULSE);
- }
-
- else if (mode == GPIO_SYNC_FALLING_TRIGER_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_UP;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_NEG_PULSE);
- }
-
- else if (mode == GPIO_SYNC_HIGH_LEVEL_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_DOWN;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_POS_LEVEL);
- }
-
- else if (mode == GPIO_SYNC_LOW_LEVEL_INT_MODE) {
- gpio_cfg.pullType = GPIO_PULL_UP;
- GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_NEG_LEVEL);
- }
-
- else {
- return;
- }
-
- break;
+ if (mode == GPIO_ASYNC_RISING_TRIGER_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_POS_PULSE);
}
- GLB_GPIO_Init(&gpio_cfg);
+ else if (mode == GPIO_ASYNC_FALLING_TRIGER_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_NEG_PULSE);
+ }
+
+ else if (mode == GPIO_ASYNC_HIGH_LEVEL_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_POS_LEVEL);
+ }
+
+ else if (mode == GPIO_ASYNC_LOW_LEVEL_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_ASYNC, GLB_GPIO_INT_TRIG_NEG_LEVEL);
+ }
+
+ else if (mode == GPIO_SYNC_RISING_TRIGER_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_POS_PULSE);
+ }
+
+ else if (mode == GPIO_SYNC_FALLING_TRIGER_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_NEG_PULSE);
+ }
+
+ else if (mode == GPIO_SYNC_HIGH_LEVEL_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_DOWN;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_POS_LEVEL);
+ }
+
+ else if (mode == GPIO_SYNC_LOW_LEVEL_INT_MODE) {
+ gpio_cfg.pullType = GPIO_PULL_UP;
+ GLB_Set_GPIO_IntMod(pin, GLB_GPIO_INT_CONTROL_SYNC, GLB_GPIO_INT_TRIG_NEG_LEVEL);
+ }
+
+ else {
+ return;
+ }
+
+ break;
+ }
+
+ GLB_GPIO_Init(&gpio_cfg);
}
/**
* @brief
@@ -142,27 +141,25 @@ void gpio_set_mode(uint32_t pin, uint32_t mode)
* @param pin
* @param value
*/
-void gpio_write(uint32_t pin, uint32_t value)
-{
- uint32_t tmp = BL_RD_REG(GLB_BASE, GLB_GPIO_OUTPUT);
+void gpio_write(uint32_t pin, uint32_t value) {
+ uint32_t tmp = BL_RD_REG(GLB_BASE, GLB_GPIO_OUTPUT);
- if (value)
- tmp |= (1 << pin);
- else
- tmp &= ~(1 << pin);
+ if (value)
+ tmp |= (1 << pin);
+ else
+ tmp &= ~(1 << pin);
- BL_WR_REG(GLB_BASE, GLB_GPIO_OUTPUT, tmp);
+ BL_WR_REG(GLB_BASE, GLB_GPIO_OUTPUT, tmp);
}
/**
* @brief
*
* @param pin
*/
-void gpio_toggle(uint32_t pin)
-{
- uint32_t tmp = BL_RD_REG(GLB_BASE, GLB_GPIO_OUTPUT);
- tmp ^= (1 << pin);
- BL_WR_REG(GLB_BASE, GLB_GPIO_OUTPUT, tmp);
+void gpio_toggle(uint32_t pin) {
+ uint32_t tmp = BL_RD_REG(GLB_BASE, GLB_GPIO_OUTPUT);
+ tmp ^= (1 << pin);
+ BL_WR_REG(GLB_BASE, GLB_GPIO_OUTPUT, tmp);
}
/**
* @brief
@@ -170,25 +167,21 @@ void gpio_toggle(uint32_t pin)
* @param pin
* @return int
*/
-int gpio_read(uint32_t pin)
-{
- return ((BL_RD_REG(GLB_BASE, GLB_GPIO_INPUT) & (1 << pin)) ? 1 : 0);
-}
+int gpio_read(uint32_t pin) { return ((BL_RD_REG(GLB_BASE, GLB_GPIO_INPUT) & (1 << pin)) ? 1 : 0); }
/**
* @brief
*
* @param pin
* @param cbFun
*/
-void gpio_attach_irq(uint32_t pin, void (*cbfun)(uint32_t pin))
-{
- struct gpio_int_cfg_private *int_cfg = malloc(sizeof(struct gpio_int_cfg_private));
- int_cfg->cbfun = cbfun;
- int_cfg->pin = pin;
- slist_add_tail(&gpio_int_head, &int_cfg->list);
- CPU_Interrupt_Disable(GPIO_INT0_IRQn);
- Interrupt_Handler_Register(GPIO_INT0_IRQn, GPIO_IRQ);
- CPU_Interrupt_Enable(GPIO_INT0_IRQn);
+void gpio_attach_irq(uint32_t pin, void (*cbfun)(uint32_t pin)) {
+ struct gpio_int_cfg_private *int_cfg = malloc(sizeof(struct gpio_int_cfg_private));
+ int_cfg->cbfun = cbfun;
+ int_cfg->pin = pin;
+ slist_add_tail(&gpio_int_head, &int_cfg->list);
+ CPU_Interrupt_Disable(GPIO_INT0_IRQn);
+ Interrupt_Handler_Register(GPIO_INT0_IRQn, GPIO_IRQ);
+ CPU_Interrupt_Enable(GPIO_INT0_IRQn);
}
/**
* @brief
@@ -196,39 +189,36 @@ void gpio_attach_irq(uint32_t pin, void (*cbfun)(uint32_t pin))
* @param pin
* @param enabled
*/
-void gpio_irq_enable(uint32_t pin, uint8_t enabled)
-{
- if (enabled) {
- GLB_GPIO_IntMask(pin, UNMASK);
- } else {
- GLB_GPIO_IntMask(pin, MASK);
- }
+void gpio_irq_enable(uint32_t pin, uint8_t enabled) {
+ if (enabled) {
+ GLB_GPIO_IntMask(pin, UNMASK);
+ } else {
+ GLB_GPIO_IntMask(pin, MASK);
+ }
}
-static void GPIO_IRQ(void)
-{
- slist_t *i;
- uint32_t timeOut = 0;
+static void GPIO_IRQ(void) {
+ slist_t *i;
+ uint32_t timeOut = 0;
#define GLB_GPIO_INT0_CLEAR_TIMEOUT (32)
- slist_for_each(i, &gpio_int_head)
- {
- struct gpio_int_cfg_private *int_cfg = slist_entry(i, struct gpio_int_cfg_private, list);
+ slist_for_each(i, &gpio_int_head) {
+ struct gpio_int_cfg_private *int_cfg = slist_entry(i, struct gpio_int_cfg_private, list);
- if (SET == GLB_Get_GPIO_IntStatus(int_cfg->pin)) {
- int_cfg->cbfun(int_cfg->pin);
- GLB_GPIO_IntClear(int_cfg->pin, SET);
- /* timeout check */
- timeOut = GLB_GPIO_INT0_CLEAR_TIMEOUT;
+ if (SET == GLB_Get_GPIO_IntStatus(int_cfg->pin)) {
+ int_cfg->cbfun(int_cfg->pin);
+ GLB_GPIO_IntClear(int_cfg->pin, SET);
+ /* timeout check */
+ timeOut = GLB_GPIO_INT0_CLEAR_TIMEOUT;
- do {
- timeOut--;
- } while ((SET == GLB_Get_GPIO_IntStatus(int_cfg->pin)) && timeOut);
+ do {
+ timeOut--;
+ } while ((SET == GLB_Get_GPIO_IntStatus(int_cfg->pin)) && timeOut);
- if (!timeOut) {
- //MSG("WARNING: Clear GPIO interrupt status fail.\r\n");
- }
+ if (!timeOut) {
+ // MSG("WARNING: Clear GPIO interrupt status fail.\r\n");
+ }
- GLB_GPIO_IntClear(int_cfg->pin, RESET);
- }
+ GLB_GPIO_IntClear(int_cfg->pin, RESET);
}
+ }
}
\ No newline at end of file
diff --git a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_pwm.c b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_pwm.c
deleted file mode 100644
index 979e773c..00000000
--- a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/hal_drv/src/hal_pwm.c
+++ /dev/null
@@ -1,203 +0,0 @@
-/**
- * @file hal_pwm.c
- * @brief
- *
- * Copyright (c) 2021 Bouffalolab team
- *
- * Licensed to the Apache Software Foundation (ASF) under one or more
- * contributor license agreements. See the NOTICE file distributed with
- * this work for additional information regarding copyright ownership. The
- * ASF licenses this file to you under the Apache License, Version 2.0 (the
- * "License"); you may not use this file except in compliance with the
- * License. You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
- * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
- * License for the specific language governing permissions and limitations
- * under the License.
- *
- */
-#include "hal_pwm.h"
-#include "hal_clock.h"
-#include "bl702_pwm.h"
-#include "bl702_glb.h"
-
-static pwm_device_t pwmx_device[PWM_MAX_INDEX] = {
-#ifdef BSP_USING_PWM_CH0
- PWM_CH0_CONFIG,
-#endif
-#ifdef BSP_USING_PWM_CH1
- PWM_CH1_CONFIG,
-#endif
-#ifdef BSP_USING_PWM_CH2
- PWM_CH2_CONFIG,
-#endif
-#ifdef BSP_USING_PWM_CH3
- PWM_CH3_CONFIG,
-#endif
-#ifdef BSP_USING_PWM_CH4
- PWM_CH4_CONFIG,
-#endif
-};
-static void PWM_IRQ(void);
-
-int pwm_open(struct device *dev, uint16_t oflag)
-{
- pwm_device_t *pwm_device = (pwm_device_t *)dev;
-
- uint32_t tmpVal;
- uint32_t PWMx;
-
- CPU_Interrupt_Disable(PWM_IRQn);
- PWM_IntMask(pwm_device->ch, PWM_INT_ALL, MASK);
-
- PWM_Channel_Disable(pwm_device->ch);
-
- uint32_t pwm_clk = peripheral_clock_get(PERIPHERAL_CLOCK_PWM);
- if (pwm_device->period > pwm_clk)
- return -1;
-
- PWMx = PWM_BASE + PWM_CHANNEL_OFFSET + (pwm_device->ch) * 0x20;
-
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_OUT_INV, pwm_device->polarity_invert_mode);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_STOP_MODE, PWM_STOP_GRACEFUL);
- BL_WR_REG(PWMx, PWM_CONFIG, tmpVal);
-
- BL_WR_REG(PWMx, PWM_THRE1, pwm_device->threshold_low);
- BL_WR_REG(PWMx, PWM_THRE2, pwm_device->threshold_high);
- BL_WR_REG(PWMx, PWM_PERIOD, pwm_device->period);
-
- if (oflag & DEVICE_OFLAG_INT_TX) {
- tmpVal = BL_RD_REG(PWMx, PWM_INTERRUPT);
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BITS_VAL(tmpVal, PWM_INT_PERIOD_CNT, pwm_device->it_pulse_count));
- Interrupt_Handler_Register(PWM_IRQn, PWM_IRQ);
- PWM_IntMask(pwm_device->ch, PWM_INT_PULSE_CNT, UNMASK);
- CPU_Interrupt_Enable(PWM_IRQn);
- }
-
- return 0;
-}
-int pwm_close(struct device *dev)
-{
- pwm_device_t *pwm_device = (pwm_device_t *)dev;
- PWM_Channel_Disable(pwm_device->ch);
- return 0;
-}
-
-int pwm_control(struct device *dev, int cmd, void *args)
-{
- pwm_device_t *pwm_device = (pwm_device_t *)dev;
- pwm_dutycycle_config_t *config = (pwm_dutycycle_config_t *)args;
-
- switch (cmd) {
- case DEVICE_CTRL_CONFIG /* constant-expression */:
- break;
- case DEVICE_CTRL_RESUME /* constant-expression */:
- PWM_Channel_Enable(pwm_device->ch);
- break;
-
- case DEVICE_CTRL_SUSPEND /* constant-expression */:
- PWM_Channel_Disable(pwm_device->ch);
- break;
- case DEVICE_CTRL_PWM_FREQUENCE_CONFIG:
-
- if ((uint32_t)args > peripheral_clock_get(PERIPHERAL_CLOCK_PWM))
- return -1;
- pwm_device->period = (uint32_t)args;
- BL_WR_REG(PWM_BASE + PWM_CHANNEL_OFFSET + (pwm_device->ch) * 0x20, PWM_PERIOD, (uint32_t)args);
- break;
- case DEVICE_CTRL_PWM_DUTYCYCLE_CONFIG:
- BL_WR_REG(PWM_BASE + PWM_CHANNEL_OFFSET + (pwm_device->ch) * 0x20, PWM_THRE1, config->threshold_low);
- BL_WR_REG(PWM_BASE + PWM_CHANNEL_OFFSET + (pwm_device->ch) * 0x20, PWM_THRE2, config->threshold_high);
- break;
- case DEVICE_CTRL_PWM_IT_PULSE_COUNT_CONFIG: {
- /* Config interrupt pulse count */
- uint32_t pwm_ch_addr = PWM_BASE + PWM_CHANNEL_OFFSET + (pwm_device->ch) * 0x20;
- uint32_t tmpVal = BL_RD_REG(pwm_ch_addr, PWM_INTERRUPT);
- BL_WR_REG(pwm_ch_addr, PWM_INTERRUPT, BL_SET_REG_BITS_VAL(tmpVal, PWM_INT_PERIOD_CNT, (uint32_t)args));
-
- if ((uint32_t)args) {
- PWM_IntMask(pwm_device->ch, PWM_INT_PULSE_CNT, UNMASK);
- CPU_Interrupt_Enable(PWM_IRQn);
- } else {
- PWM_IntMask(pwm_device->ch, PWM_INT_PULSE_CNT, MASK);
- CPU_Interrupt_Disable(PWM_IRQn);
- }
-
- break;
- }
-
- default:
- break;
- }
-
- return 0;
-}
-
-int pwm_register(enum pwm_index_type index, const char *name)
-{
- struct device *dev;
-
- if (PWM_MAX_INDEX == 0) {
- return -DEVICE_EINVAL;
- }
-
- dev = &(pwmx_device[index].parent);
-
- dev->open = pwm_open;
- dev->close = pwm_close;
- dev->control = pwm_control;
- dev->write = NULL;
- dev->read = NULL;
-
- dev->type = DEVICE_CLASS_PWM;
- dev->handle = NULL;
-
- return device_register(dev, name);
-}
-
-static void pwm_isr(pwm_device_t *handle)
-{
- uint32_t i;
- uint32_t tmpVal;
- uint32_t timeoutCnt = 160 * 1000;
- /* Get channel register */
- uint32_t PWMx = PWM_BASE;
-
- for (i = 0; i < PWM_MAX_INDEX; i++) {
- tmpVal = BL_RD_REG(PWMx, PWM_INT_CONFIG);
-
- if ((BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << handle[i].ch)) != 0) {
- /* Clear interrupt */
- tmpVal |= (1 << (handle[i].ch + PWM_INT_CLEAR_POS));
- BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
-
- /* FIXME: we need set pwm_int_clear to 0 by software and
- before this,we must make sure pwm_interrupt_sts is 0*/
- do {
- tmpVal = BL_RD_REG(PWMx, PWM_INT_CONFIG);
- timeoutCnt--;
-
- if (timeoutCnt == 0) {
- break;
- }
- } while (BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << handle[i].ch));
-
- tmpVal &= (~(1 << (handle[i].ch + PWM_INT_CLEAR_POS)));
- BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
-
- if (handle[i].parent.callback) {
- handle[i].parent.callback(&handle[i].parent, NULL, 0, PWM_EVENT_COMPLETE);
- }
- }
- }
-}
-
-static void PWM_IRQ(void)
-{
- pwm_isr(&pwmx_device[0]);
-}
\ No newline at end of file
diff --git a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_glb.c b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_glb.c
index dc2bab72..97c6d769 100644
--- a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_glb.c
+++ b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_glb.c
@@ -3252,7 +3252,7 @@ BL_Err_Type GLB_GPIO_Func_Init(GLB_GPIO_FUNC_Type gpioFun, GLB_GPIO_Type *pinLis
.gpioFun = (uint8_t)gpioFun,
.gpioMode = GPIO_MODE_AF,
.pullType = GPIO_PULL_UP,
- .drive = 1,
+ .drive = 3,
.smtCtrl = 1
};
diff --git a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_pwm.c b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_pwm.c
index bf2ab16e..f131326f 100644
--- a/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_pwm.c
+++ b/source/Core/BSP/Magic/bl_mcu_sdk/drivers/bl702_driver/std_drv/src/bl702_pwm.c
@@ -1,38 +1,38 @@
/**
- ******************************************************************************
- * @file bl702_pwm.c
- * @version V1.0
- * @date
- * @brief This file is the standard driver c file
- ******************************************************************************
- * @attention
- *
- *
© COPYRIGHT(c) 2020 Bouffalo Lab
- *
- * 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 Bouffalo Lab 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.
- *
- ******************************************************************************
- */
+ ******************************************************************************
+ * @file bl702_pwm.c
+ * @version V1.0
+ * @date
+ * @brief This file is the standard driver c file
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2020 Bouffalo Lab
+ *
+ * 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 Bouffalo Lab 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 "bl702_pwm.h"
#include "bl702_glb.h"
@@ -67,9 +67,7 @@
/**
* @brief PWM interrupt callback function address array
*/
-static intCallback_Type *PWMIntCbfArra[PWM_CH_MAX][PWM_INT_ALL] = {
- { NULL }
-};
+static intCallback_Type *PWMIntCbfArra[PWM_CH_MAX][PWM_INT_ALL] = {{NULL}};
/*@} end of group PWM_Private_Variables */
@@ -93,52 +91,51 @@ static BL_Err_Type PWM_IntHandler(IRQn_Type intPeriph);
*/
/****************************************************************************/ /**
- * @brief PWM interrupt handle
- *
- * @param intPeriph: Select the peripheral, such as PWM0_IRQn
- *
- * @return SUCCESS
- *
-*******************************************************************************/
+ * @brief PWM interrupt handle
+ *
+ * @param intPeriph: Select the peripheral, such as PWM0_IRQn
+ *
+ * @return SUCCESS
+ *
+ *******************************************************************************/
#ifndef BFLB_USE_HAL_DRIVER
-static BL_Err_Type PWM_IntHandler(IRQn_Type intPeriph)
-{
- uint32_t i;
- uint32_t tmpVal;
- uint32_t timeoutCnt = PWM_INT_TIMEOUT_COUNT;
- /* Get channel register */
- uint32_t PWMx = PWM_BASE;
+static BL_Err_Type PWM_IntHandler(IRQn_Type intPeriph) {
+ uint32_t i;
+ uint32_t tmpVal;
+ uint32_t timeoutCnt = PWM_INT_TIMEOUT_COUNT;
+ /* Get channel register */
+ uint32_t PWMx = PWM_BASE;
- for (i = 0; i < PWM_CH_MAX; i++) {
+ for (i = 0; i < PWM_CH_MAX; i++) {
+ tmpVal = BL_RD_REG(PWMx, PWM_INT_CONFIG);
+
+ if ((BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << i)) != 0) {
+ /* Clear interrupt */
+ tmpVal |= (1 << (i + PWM_INT_CLEAR_POS));
+ BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
+
+ /* FIXME: we need set pwm_int_clear to 0 by software and
+ before this,we must make sure pwm_interrupt_sts is 0*/
+ do {
tmpVal = BL_RD_REG(PWMx, PWM_INT_CONFIG);
+ timeoutCnt--;
- if ((BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << i)) != 0) {
- /* Clear interrupt */
- tmpVal |= (1 << (i + PWM_INT_CLEAR_POS));
- BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
-
- /* FIXME: we need set pwm_int_clear to 0 by software and
- before this,we must make sure pwm_interrupt_sts is 0*/
- do {
- tmpVal = BL_RD_REG(PWMx, PWM_INT_CONFIG);
- timeoutCnt--;
-
- if (timeoutCnt == 0) {
- break;
- }
- } while (BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << i));
-
- tmpVal &= (~(1 << (i + PWM_INT_CLEAR_POS)));
- BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
-
- if (PWMIntCbfArra[i][PWM_INT_PULSE_CNT] != NULL) {
- /* Call the callback function */
- PWMIntCbfArra[i][PWM_INT_PULSE_CNT]();
- }
+ if (timeoutCnt == 0) {
+ break;
}
- }
+ } while (BL_GET_REG_BITS_VAL(tmpVal, PWM_INTERRUPT_STS) & (1 << i));
- return SUCCESS;
+ tmpVal &= (~(1 << (i + PWM_INT_CLEAR_POS)));
+ BL_WR_REG(PWMx, PWM_INT_CONFIG, tmpVal);
+
+ if (PWMIntCbfArra[i][PWM_INT_PULSE_CNT] != NULL) {
+ /* Call the callback function */
+ PWMIntCbfArra[i][PWM_INT_PULSE_CNT]();
+ }
+ }
+ }
+
+ return SUCCESS;
}
#endif
@@ -149,462 +146,443 @@ static BL_Err_Type PWM_IntHandler(IRQn_Type intPeriph)
*/
/****************************************************************************/ /**
- * @brief PWM channel init
- *
- * @param chCfg: PWM configuration
- *
- * @return SUCCESS
- *
-*******************************************************************************/
-BL_Err_Type PWM_Channel_Init(PWM_CH_CFG_Type *chCfg)
-{
- uint32_t tmpVal;
- uint32_t timeoutCnt = PWM_STOP_TIMEOUT_COUNT;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(chCfg->ch);
+ * @brief PWM channel init
+ *
+ * @param chCfg: PWM configuration
+ *
+ * @return SUCCESS
+ *
+ *******************************************************************************/
+BL_Err_Type PWM_Channel_Init(PWM_CH_CFG_Type *chCfg) {
+ uint32_t tmpVal;
+ uint32_t timeoutCnt = PWM_STOP_TIMEOUT_COUNT;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(chCfg->ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(chCfg->ch));
- CHECK_PARAM(IS_PWM_CLK_TYPE(chCfg->clk));
- CHECK_PARAM(IS_PWM_POLARITY_TYPE(chCfg->pol));
- CHECK_PARAM(IS_PWM_STOP_MODE_TYPE(chCfg->stopMode));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(chCfg->ch));
+ CHECK_PARAM(IS_PWM_CLK_TYPE(chCfg->clk));
+ CHECK_PARAM(IS_PWM_POLARITY_TYPE(chCfg->pol));
+ CHECK_PARAM(IS_PWM_STOP_MODE_TYPE(chCfg->stopMode));
- /* Disable clock gate */
- GLB_AHB_Slave1_Clock_Gate(DISABLE, BL_AHB_SLAVE1_PWM);
+ /* Disable clock gate */
+ GLB_AHB_Slave1_Clock_Gate(DISABLE, BL_AHB_SLAVE1_PWM);
- /* Config pwm clock and polarity */
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
+ /* Config pwm clock and polarity */
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
- while (!BL_IS_REG_BIT_SET(BL_RD_REG(PWMx, PWM_CONFIG), PWM_STS_TOP)) {
- timeoutCnt--;
+ while (!BL_IS_REG_BIT_SET(BL_RD_REG(PWMx, PWM_CONFIG), PWM_STS_TOP)) {
+ timeoutCnt--;
- if (timeoutCnt == 0) {
- return TIMEOUT;
- }
+ if (timeoutCnt == 0) {
+ return TIMEOUT;
}
+ }
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL, chCfg->clk);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_OUT_INV, chCfg->pol);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_STOP_MODE, chCfg->stopMode);
- BL_WR_REG(PWMx, PWM_CONFIG, tmpVal);
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL, chCfg->clk);
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_OUT_INV, chCfg->pol);
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_STOP_MODE, chCfg->stopMode);
+ BL_WR_REG(PWMx, PWM_CONFIG, tmpVal);
- /* Config pwm division */
- BL_WR_REG(PWMx, PWM_CLKDIV, chCfg->clkDiv);
+ /* Config pwm division */
+ BL_WR_REG(PWMx, PWM_CLKDIV, chCfg->clkDiv);
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_THRE1, chCfg->threshold1);
- BL_WR_REG(PWMx, PWM_THRE2, chCfg->threshold2);
- BL_WR_REG(PWMx, PWM_PERIOD, chCfg->period);
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_THRE1, chCfg->threshold1);
+ BL_WR_REG(PWMx, PWM_THRE2, chCfg->threshold2);
+ BL_WR_REG(PWMx, PWM_PERIOD, chCfg->period);
- /* Config interrupt pulse count */
- tmpVal = BL_RD_REG(PWMx, PWM_INTERRUPT);
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BITS_VAL(tmpVal, PWM_INT_PERIOD_CNT, chCfg->intPulseCnt));
- PWM_IntMask(chCfg->ch, PWM_INT_PULSE_CNT, chCfg->intPulseCnt != 0 ? UNMASK : MASK);
+ /* Config interrupt pulse count */
+ tmpVal = BL_RD_REG(PWMx, PWM_INTERRUPT);
+ BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BITS_VAL(tmpVal, PWM_INT_PERIOD_CNT, chCfg->intPulseCnt));
+ // PWM_IntMask(chCfg->ch, PWM_INT_PULSE_CNT, chCfg->intPulseCnt != 0 ? UNMASK : MASK);
+ CPU_Interrupt_Disable(PWM_IRQn);
-#ifndef BFLB_USE_HAL_DRIVER
- Interrupt_Handler_Register(PWM_IRQn, PWM_IRQHandler);
-#endif
+ // #ifndef BFLB_USE_HAL_DRIVER
+ // Interrupt_Handler_Register(PWM_IRQn, PWM_IRQHandler);
+ // #endif
- return SUCCESS;
+ return SUCCESS;
}
/****************************************************************************/ /**
- * @brief PWM channel update source memory address and len
- *
- * @param ch: PWM channel
- * @param period: period
- * @param threshold1: threshold1
- * @param threshold2: threshold2
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Update(PWM_CH_ID_Type ch, uint16_t period, uint16_t threshold1, uint16_t threshold2)
-{
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel update source memory address and len
+ *
+ * @param ch: PWM channel
+ * @param period: period
+ * @param threshold1: threshold1
+ * @param threshold2: threshold2
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Update(PWM_CH_ID_Type ch, uint16_t period, uint16_t threshold1, uint16_t threshold2) {
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_THRE1, threshold1);
- BL_WR_REG(PWMx, PWM_THRE2, threshold2);
- BL_WR_REG(PWMx, PWM_PERIOD, period);
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_THRE1, threshold1);
+ BL_WR_REG(PWMx, PWM_THRE2, threshold2);
+ BL_WR_REG(PWMx, PWM_PERIOD, period);
}
/****************************************************************************/ /**
- * @brief PWM channel update clock divider
- *
- * @param ch: PWM channel
- * @param div: Clock divider
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Set_Div(PWM_CH_ID_Type ch, uint16_t div)
-{
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel update clock divider
+ *
+ * @param ch: PWM channel
+ * @param div: Clock divider
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Set_Div(PWM_CH_ID_Type ch, uint16_t div) {
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- BL_WR_REG(PWMx, PWM_CLKDIV, div);
+ BL_WR_REG(PWMx, PWM_CLKDIV, div);
}
/****************************************************************************/ /**
- * @brief PWM channel update threshold1
- *
- * @param ch: PWM channel
- * @param threshold1: threshold1
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Set_Threshold1(PWM_CH_ID_Type ch, uint16_t threshold1)
-{
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel update threshold1
+ *
+ * @param ch: PWM channel
+ * @param threshold1: threshold1
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Set_Threshold1(PWM_CH_ID_Type ch, uint16_t threshold1) {
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_THRE1, threshold1);
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_THRE1, threshold1);
}
/****************************************************************************/ /**
- * @brief PWM channel update threshold2
- *
- * @param ch: PWM channel
- * @param threshold2: threshold2
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Set_Threshold2(PWM_CH_ID_Type ch, uint16_t threshold2)
-{
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel update threshold2
+ *
+ * @param ch: PWM channel
+ * @param threshold2: threshold2
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Set_Threshold2(PWM_CH_ID_Type ch, uint16_t threshold2) {
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_THRE2, threshold2);
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_THRE2, threshold2);
}
/****************************************************************************/ /**
- * @brief PWM channel update period
- *
- * @param ch: PWM channel
- * @param period: period
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Set_Period(PWM_CH_ID_Type ch, uint16_t period)
-{
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel update period
+ *
+ * @param ch: PWM channel
+ * @param period: period
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Set_Period(PWM_CH_ID_Type ch, uint16_t period) {
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_PERIOD, period);
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_PERIOD, period);
}
/****************************************************************************/ /**
- * @brief PWM get configuration
- *
- * @param ch: PWM channel
- * @param period: period pointer
- * @param threshold1: threshold1 pointer
- * @param threshold2: threshold2 pointer
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Get(PWM_CH_ID_Type ch, uint16_t *period, uint16_t *threshold1, uint16_t *threshold2)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM get configuration
+ *
+ * @param ch: PWM channel
+ * @param period: period pointer
+ * @param threshold1: threshold1 pointer
+ * @param threshold2: threshold2 pointer
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Get(PWM_CH_ID_Type ch, uint16_t *period, uint16_t *threshold1, uint16_t *threshold2) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* get pwm period and duty */
- tmpVal = BL_RD_REG(PWMx, PWM_THRE1);
- *threshold1 = BL_GET_REG_BITS_VAL(tmpVal, PWM_THRE1);
- tmpVal = BL_RD_REG(PWMx, PWM_THRE2);
- *threshold2 = BL_GET_REG_BITS_VAL(tmpVal, PWM_THRE2);
- tmpVal = BL_RD_REG(PWMx, PWM_PERIOD);
- *period = BL_GET_REG_BITS_VAL(tmpVal, PWM_PERIOD);
+ /* get pwm period and duty */
+ tmpVal = BL_RD_REG(PWMx, PWM_THRE1);
+ *threshold1 = BL_GET_REG_BITS_VAL(tmpVal, PWM_THRE1);
+ tmpVal = BL_RD_REG(PWMx, PWM_THRE2);
+ *threshold2 = BL_GET_REG_BITS_VAL(tmpVal, PWM_THRE2);
+ tmpVal = BL_RD_REG(PWMx, PWM_PERIOD);
+ *period = BL_GET_REG_BITS_VAL(tmpVal, PWM_PERIOD);
}
/****************************************************************************/ /**
- * @brief PWM enable
- *
- * @param ch: PWM channel number
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Enable(PWM_CH_ID_Type ch)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM enable
+ *
+ * @param ch: PWM channel number
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Enable(PWM_CH_ID_Type ch) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm clock to enable pwm */
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_CLR_REG_BIT(tmpVal, PWM_STOP_EN));
+ /* Config pwm clock to enable pwm */
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_CLR_REG_BIT(tmpVal, PWM_STOP_EN));
}
/****************************************************************************/ /**
- * @brief PWM disable
- *
- * @param ch: PWM channel number
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Disable(PWM_CH_ID_Type ch)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM disable
+ *
+ * @param ch: PWM channel number
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Disable(PWM_CH_ID_Type ch) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- /* Config pwm clock to disable pwm */
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
- PWM_IntMask(ch, PWM_INT_PULSE_CNT, MASK);
+ /* Config pwm clock to disable pwm */
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
+ PWM_IntMask(ch, PWM_INT_PULSE_CNT, MASK);
}
/****************************************************************************/ /**
- * @brief PWM channel software mode enable or disable
- *
- * @param ch: PWM channel number
- * @param enable: Enable or disable
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_SW_Mode(PWM_CH_ID_Type ch, BL_Fun_Type enable)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel software mode enable or disable
+ *
+ * @param ch: PWM channel number
+ * @param enable: Enable or disable
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_SW_Mode(PWM_CH_ID_Type ch, BL_Fun_Type enable) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BITS_VAL(tmpVal, PWM_SW_MODE, enable));
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BITS_VAL(tmpVal, PWM_SW_MODE, enable));
}
/****************************************************************************/ /**
- * @brief PWM channel force output high or low
- *
- * @param ch: PWM channel number
- * @param value: Output value
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_SW_Force_Value(PWM_CH_ID_Type ch, uint8_t value)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel force output high or low
+ *
+ * @param ch: PWM channel number
+ * @param value: Output value
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_SW_Force_Value(PWM_CH_ID_Type ch, uint8_t value) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BITS_VAL(tmpVal, PWM_SW_FORCE_VAL, value));
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BITS_VAL(tmpVal, PWM_SW_FORCE_VAL, value));
}
/****************************************************************************/ /**
- * @brief PWM channel force output high
- *
- * @param ch: PWM channel number
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Channel_Fource_Output(PWM_CH_ID_Type ch)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief PWM channel force output high
+ *
+ * @param ch: PWM channel number
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Channel_Fource_Output(PWM_CH_ID_Type ch) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_SW_MODE));
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_SW_MODE));
}
/****************************************************************************/ /**
- * @brief Mask/Unmask the PWM interrupt
- *
- * @param ch: PWM channel number
- * @param intType: Specifies the interrupt type
- * @param intMask: Enable/Disable Specified interrupt type
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_IntMask(PWM_CH_ID_Type ch, PWM_INT_Type intType, BL_Mask_Type intMask)
-{
- uint32_t tmpVal;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+ * @brief Mask/Unmask the PWM interrupt
+ *
+ * @param ch: PWM channel number
+ * @param intType: Specifies the interrupt type
+ * @param intMask: Enable/Disable Specified interrupt type
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_IntMask(PWM_CH_ID_Type ch, PWM_INT_Type intType, BL_Mask_Type intMask) {
+ uint32_t tmpVal;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
- /* Check the parameters */
- CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
- CHECK_PARAM(IS_PWM_INT_TYPE(intType));
+ /* Check the parameters */
+ CHECK_PARAM(IS_PWM_CH_ID_TYPE(ch));
+ CHECK_PARAM(IS_PWM_INT_TYPE(intType));
- tmpVal = BL_RD_REG(PWMx, PWM_INTERRUPT);
+ tmpVal = BL_RD_REG(PWMx, PWM_INTERRUPT);
- switch (intType) {
- case PWM_INT_PULSE_CNT:
- if (intMask == UNMASK) {
- /* UNMASK(Enable) this interrupt */
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BIT(tmpVal, PWM_INT_ENABLE));
- } else {
- /* MASK(Disable) this interrupt */
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_CLR_REG_BIT(tmpVal, PWM_INT_ENABLE));
- }
-
- break;
-
- case PWM_INT_ALL:
- if (intMask == UNMASK) {
- /* UNMASK(Enable) this interrupt */
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BIT(tmpVal, PWM_INT_ENABLE));
- } else {
- /* MASK(Disable) this interrupt */
- BL_WR_REG(PWMx, PWM_INTERRUPT, BL_CLR_REG_BIT(tmpVal, PWM_INT_ENABLE));
- }
-
- break;
-
- default:
- break;
- }
-}
-
-/****************************************************************************/ /**
- * @brief Install PWM interrupt callback function
- *
- * @param ch: PWM channel number
- * @param intType: PWM interrupt type
- * @param cbFun: Pointer to interrupt callback function. The type should be void (*fn)(void)
- *
- * @return None
- *
-*******************************************************************************/
-void PWM_Int_Callback_Install(PWM_CH_ID_Type ch, uint32_t intType, intCallback_Type *cbFun)
-{
- PWMIntCbfArra[ch][intType] = cbFun;
-}
-
-/****************************************************************************/ /**
- * @brief PWM smart configure according to frequency and duty cycle function
- *
- * @param ch: PWM channel number
- * @param frequency: PWM frequency
- * @param dutyCycle: PWM duty cycle
- *
- * @return SUCCESS or TIMEOUT
- *
-*******************************************************************************/
-BL_Err_Type PWM_Smart_Configure(PWM_CH_ID_Type ch, uint32_t frequency, uint8_t dutyCycle)
-{
- uint32_t tmpVal;
- uint16_t clkDiv, period, threshold2;
- uint32_t timeoutCnt = PWM_STOP_TIMEOUT_COUNT;
- /* Get channel register */
- uint32_t PWMx = PWM_Get_Channel_Reg(ch);
-
- if (frequency <= 32) {
- clkDiv = 500;
- period = 64000 / frequency;
- threshold2 = 640 * dutyCycle / frequency;
- } else if (frequency <= 62) {
- clkDiv = 16;
- period = 2000000 / frequency;
- threshold2 = 20000 * dutyCycle / frequency;
- } else if (frequency <= 124) {
- clkDiv = 8;
- period = 4000000 / frequency;
- threshold2 = 40000 * dutyCycle / frequency;
- } else if (frequency <= 246) {
- clkDiv = 4;
- period = 8000000 / frequency;
- threshold2 = 80000 * dutyCycle / frequency;
- } else if (frequency <= 490) {
- clkDiv = 2;
- period = 16000000 / frequency;
- threshold2 = 160000 * dutyCycle / frequency;
+ switch (intType) {
+ case PWM_INT_PULSE_CNT:
+ if (intMask == UNMASK) {
+ /* UNMASK(Enable) this interrupt */
+ BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BIT(tmpVal, PWM_INT_ENABLE));
} else {
- clkDiv = 1;
- period = 32000000 / frequency;
- threshold2 = 320000 * dutyCycle / frequency;
+ /* MASK(Disable) this interrupt */
+ BL_WR_REG(PWMx, PWM_INTERRUPT, BL_CLR_REG_BIT(tmpVal, PWM_INT_ENABLE));
}
- tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
- if (BL_GET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL) != PWM_CLK_XCLK) {
- BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
- while (!BL_IS_REG_BIT_SET(BL_RD_REG(PWMx, PWM_CONFIG), PWM_STS_TOP)) {
- timeoutCnt--;
- if (timeoutCnt == 0) {
- return TIMEOUT;
- }
- }
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL, PWM_CLK_XCLK);
+ break;
+
+ case PWM_INT_ALL:
+ if (intMask == UNMASK) {
+ /* UNMASK(Enable) this interrupt */
+ BL_WR_REG(PWMx, PWM_INTERRUPT, BL_SET_REG_BIT(tmpVal, PWM_INT_ENABLE));
+ } else {
+ /* MASK(Disable) this interrupt */
+ BL_WR_REG(PWMx, PWM_INTERRUPT, BL_CLR_REG_BIT(tmpVal, PWM_INT_ENABLE));
}
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_OUT_INV, PWM_POL_NORMAL);
- tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_STOP_MODE, PWM_STOP_GRACEFUL);
- BL_WR_REG(PWMx, PWM_CONFIG, tmpVal);
- /* Config pwm division */
- BL_WR_REG(PWMx, PWM_CLKDIV, clkDiv);
+ break;
- /* Config pwm period and duty */
- BL_WR_REG(PWMx, PWM_PERIOD, period);
- BL_WR_REG(PWMx, PWM_THRE1, 0);
- BL_WR_REG(PWMx, PWM_THRE2, threshold2);
-
- return SUCCESS;
+ default:
+ break;
+ }
}
/****************************************************************************/ /**
- * @brief PWM interrupt function
- *
- * @param None
- *
- * @return None
- *
-*******************************************************************************/
-#ifndef BFLB_USE_HAL_DRIVER
-void PWM_IRQHandler(void)
-{
- PWM_IntHandler(PWM_IRQn);
+ * @brief Install PWM interrupt callback function
+ *
+ * @param ch: PWM channel number
+ * @param intType: PWM interrupt type
+ * @param cbFun: Pointer to interrupt callback function. The type should be void (*fn)(void)
+ *
+ * @return None
+ *
+ *******************************************************************************/
+void PWM_Int_Callback_Install(PWM_CH_ID_Type ch, uint32_t intType, intCallback_Type *cbFun) { PWMIntCbfArra[ch][intType] = cbFun; }
+
+/****************************************************************************/ /**
+ * @brief PWM smart configure according to frequency and duty cycle function
+ *
+ * @param ch: PWM channel number
+ * @param frequency: PWM frequency
+ * @param dutyCycle: PWM duty cycle
+ *
+ * @return SUCCESS or TIMEOUT
+ *
+ *******************************************************************************/
+BL_Err_Type PWM_Smart_Configure(PWM_CH_ID_Type ch, uint32_t frequency, uint8_t dutyCycle) {
+ uint32_t tmpVal;
+ uint16_t clkDiv, period, threshold2;
+ uint32_t timeoutCnt = PWM_STOP_TIMEOUT_COUNT;
+ /* Get channel register */
+ uint32_t PWMx = PWM_Get_Channel_Reg(ch);
+
+ if (frequency <= 32) {
+ clkDiv = 500;
+ period = 64000 / frequency;
+ threshold2 = 640 * dutyCycle / frequency;
+ } else if (frequency <= 62) {
+ clkDiv = 16;
+ period = 2000000 / frequency;
+ threshold2 = 20000 * dutyCycle / frequency;
+ } else if (frequency <= 124) {
+ clkDiv = 8;
+ period = 4000000 / frequency;
+ threshold2 = 40000 * dutyCycle / frequency;
+ } else if (frequency <= 246) {
+ clkDiv = 4;
+ period = 8000000 / frequency;
+ threshold2 = 80000 * dutyCycle / frequency;
+ } else if (frequency <= 490) {
+ clkDiv = 2;
+ period = 16000000 / frequency;
+ threshold2 = 160000 * dutyCycle / frequency;
+ } else {
+ clkDiv = 1;
+ period = 32000000 / frequency;
+ threshold2 = 320000 * dutyCycle / frequency;
+ }
+
+ tmpVal = BL_RD_REG(PWMx, PWM_CONFIG);
+ if (BL_GET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL) != PWM_CLK_XCLK) {
+ BL_WR_REG(PWMx, PWM_CONFIG, BL_SET_REG_BIT(tmpVal, PWM_STOP_EN));
+ while (!BL_IS_REG_BIT_SET(BL_RD_REG(PWMx, PWM_CONFIG), PWM_STS_TOP)) {
+ timeoutCnt--;
+ if (timeoutCnt == 0) {
+ return TIMEOUT;
+ }
+ }
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_REG_CLK_SEL, PWM_CLK_XCLK);
+ }
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_OUT_INV, PWM_POL_NORMAL);
+ tmpVal = BL_SET_REG_BITS_VAL(tmpVal, PWM_STOP_MODE, PWM_STOP_GRACEFUL);
+ BL_WR_REG(PWMx, PWM_CONFIG, tmpVal);
+
+ /* Config pwm division */
+ BL_WR_REG(PWMx, PWM_CLKDIV, clkDiv);
+
+ /* Config pwm period and duty */
+ BL_WR_REG(PWMx, PWM_PERIOD, period);
+ BL_WR_REG(PWMx, PWM_THRE1, 0);
+ BL_WR_REG(PWMx, PWM_THRE2, threshold2);
+
+ return SUCCESS;
}
+
+/****************************************************************************/ /**
+ * @brief PWM interrupt function
+ *
+ * @param None
+ *
+ * @return None
+ *
+ *******************************************************************************/
+#ifndef BFLB_USE_HAL_DRIVER
+void PWM_IRQHandler(void) { PWM_IntHandler(PWM_IRQn); }
#endif
/*@} end of group PWM_Public_Functions */
diff --git a/source/Core/BSP/Magic/clock_config.h b/source/Core/BSP/Magic/clock_config.h
index 84b7e7cf..ccd9beba 100644
--- a/source/Core/BSP/Magic/clock_config.h
+++ b/source/Core/BSP/Magic/clock_config.h
@@ -44,8 +44,8 @@
#define BSP_TIMER1_CLOCK_DIV 31
#define BSP_WDT_CLOCK_SOURCE ROOT_CLOCK_SOURCE_FCLK
#define BSP_WDT_CLOCK_DIV 0
-#define BSP_PWM_CLOCK_SOURCE ROOT_CLOCK_SOURCE_32K_CLK
-#define BSP_PWM_CLOCK_DIV 31
+#define BSP_PWM_CLOCK_SOURCE ROOT_CLOCK_SOURCE_XCLK
+#define BSP_PWM_CLOCK_DIV 22
#define BSP_IR_CLOCK_SOURCE ROOT_CLOCK_SOURCE_XCLK
#define BSP_IR_CLOCK_DIV 0
#define BSP_ADC_CLOCK_SOURCE ROOT_CLOCK_SOURCE_XCLK
diff --git a/source/Core/BSP/Magic/peripheral_config.h b/source/Core/BSP/Magic/peripheral_config.h
index 60554ebb..b5525b37 100644
--- a/source/Core/BSP/Magic/peripheral_config.h
+++ b/source/Core/BSP/Magic/peripheral_config.h
@@ -32,11 +32,11 @@
// #define BSP_USING_SPI0
#define BSP_USING_I2C0
// #define BSP_USING_I2S0
-#define BSP_USING_PWM_CH0
+// #define BSP_USING_PWM_CH0
#define BSP_USING_PWM_CH1
-#define BSP_USING_PWM_CH2
-#define BSP_USING_PWM_CH3
-#define BSP_USING_PWM_CH4
+// #define BSP_USING_PWM_CH2
+// #define BSP_USING_PWM_CH3
+// #define BSP_USING_PWM_CH4
#define BSP_USING_TIMER0
#define BSP_USING_TIMER1
#define BSP_USING_WDT
@@ -93,7 +93,7 @@
#if defined(BSP_USING_PWM_CH1)
#ifndef PWM_CH1_CONFIG
#define PWM_CH1_CONFIG \
- { .ch = 1, .polarity_invert_mode = DISABLE, .period = 0, .threshold_low = 0, .threshold_high = 0, .it_pulse_count = 0, }
+ { .ch = 1, .polarity_invert_mode = DISABLE, .period = 100, .threshold_low = 50, .threshold_high = 0, .it_pulse_count = 0, }
#endif
#endif
diff --git a/source/Core/BSP/Magic/pinmux_config.h b/source/Core/BSP/Magic/pinmux_config.h
index c710ff22..9fa10ec0 100644
--- a/source/Core/BSP/Magic/pinmux_config.h
+++ b/source/Core/BSP/Magic/pinmux_config.h
@@ -109,7 +109,7 @@
// GPIO21 <2> [GPIO_FUN_UNUSED//GPIO_FUN_I2S//GPIO_FUN_SPI//GPIO_FUN_I2C//GPIO_FUN_PWM//GPIO_FUN_CAM//GPIO_FUN_USB//GPIO_FUN_UART0_RTS//GPIO_FUN_UART1_RTS//GPIO_FUN_ETHER_MAC//GPIO_FUN_QDEC]
// config gpio21 function
-#define CONFIG_GPIO21_FUNC GPIO_FUN_PWM
+#define CONFIG_GPIO21_FUNC GPIO21_FUN_PWM_CH1
// GPIO22 <2> [GPIO_FUN_UNUSED//GPIO_FUN_I2S//GPIO_FUN_SPI//GPIO_FUN_I2C//GPIO_FUN_PWM//GPIO_FUN_CAM//GPIO_FUN_USB//GPIO_FUN_UART0_RTS//GPIO_FUN_UART1_RTS//GPIO_FUN_ETHER_MAC//GPIO_FUN_QDEC]
// config gpio22 function
diff --git a/source/Core/Drivers/USBPD.cpp b/source/Core/Drivers/USBPD.cpp
index c7295ee9..1c404cad 100644
--- a/source/Core/Drivers/USBPD.cpp
+++ b/source/Core/Drivers/USBPD.cpp
@@ -20,10 +20,8 @@
void ms_delay(uint32_t delayms) {
// Convert ms -> ticks
TickType_t ticks = delayms / portTICK_PERIOD_MS;
- MSG((char *)"USB PD Delay %ld\r\n", ticks);
vTaskDelay(ticks ? ticks : 1); /* Minimum delay = 1 tick */
- MSG((char *)"USB PD Delay %d...Done\r\n", delayms);
}
uint32_t get_ms_timestamp() {
// Convert ticks -> ms