examples: replace legacy timer group with gptimer

This commit is contained in:
morris 2022-01-02 16:19:06 +08:00
parent 02f6b83f47
commit 6bf3af7c8e
20 changed files with 523 additions and 1454 deletions

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -7,16 +7,12 @@
#ifndef __IOT_LED_H__
#define __IOT_LED_H__
#include "driver/ledc.h"
#ifdef __cplusplus
extern "C" {
#endif
#include "driver/ledc.h"
#define HW_TIMER_GROUP (0) /**< Hardware timer group */
#define HW_TIMER_ID (0) /**< Hardware timer number */
#define HW_TIMER_DIVIDER (16) /**< Hardware timer clock divider */
#define HW_TIMER_SCALE (TIMER_BASE_CLK / HW_TIMER_DIVIDER) /**< Convert counter value to seconds */
#define GAMMA_CORRECTION 0.8 /**< Gamma curve parameter */
#define GAMMA_TABLE_SIZE 256 /**< Gamma table size, used for led fade*/
#define DUTY_SET_CYCLE (20) /**< Set duty cycle */

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -7,26 +7,14 @@
#ifndef __IOT_LIGHT_H__
#define __IOT_LIGHT_H__
#include "driver/ledc.h"
#ifdef __cplusplus
extern "C" {
#endif
#include "driver/ledc.h"
/********************************** NOTE *********************************/
/* When we create a light object, a hardware timer will be enabled, this */
/* timer is used to realize fade and blink operation. The default timer */
/* occupied is timer 0 of timer group 0, user can change this config in */
/* menuconfig. */
/*************************************************************************/
typedef void *light_handle_t;
#define HW_TIMER_GROUP (0) /**< Hardware timer group */
#define HW_TIMER_ID (0) /**< Hardware timer number */
#define HW_TIMER_DIVIDER (16) /**< Hardware timer clock divider */
#define HW_TIMER_SCALE (TIMER_BASE_CLK / HW_TIMER_DIVIDER) /**< Convert counter value to seconds */
#define DUTY_SET_CYCLE (20) /**< Set duty cycle */
#define DUTY_SET_GAMMA (0.6) /**< Set the Gamma value for the fade curve, default value is 0.6 */

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -7,13 +7,12 @@
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "errno.h"
#include "math.h"
#include <errno.h>
#include <math.h>
#include "soc/ledc_reg.h"
#include "soc/timer_group_struct.h"
#include "soc/ledc_struct.h"
#include "driver/timer.h"
#include "driver/gptimer.h"
#include "driver/ledc.h"
#include "iot_led.h"
#include "esp_log.h"
@ -27,6 +26,8 @@
#define GET_FIXED_INTEGER_PART(X, Q) (X >> Q)
#define GET_FIXED_DECIMAL_PART(X, Q) (X & ((0x1U << Q) - 1))
#define GPTIMER_RESOLUTION_HZ 1000000 // 1MHz, 1 tick=1us
typedef struct {
int cur;
int final;
@ -35,16 +36,11 @@ typedef struct {
size_t num;
} ledc_fade_data_t;
typedef struct {
timer_group_t timer_group;
timer_idx_t timer_id;
} hw_timer_idx_t;
typedef struct {
ledc_fade_data_t fade_data[LEDC_CHANNEL_MAX];
ledc_mode_t speed_mode;
ledc_timer_t timer_num;
hw_timer_idx_t timer_id;
gptimer_handle_t gptimer;
} iot_light_t;
static const char *TAG = "iot_light";
@ -52,40 +48,27 @@ static DRAM_ATTR iot_light_t *g_light_config = NULL;
static DRAM_ATTR uint16_t *g_gamma_table = NULL;
static DRAM_ATTR bool g_hw_timer_started = false;
static void iot_timer_create(hw_timer_idx_t *timer_id, bool auto_reload,
uint32_t timer_interval_ms, void *isr_handle)
static IRAM_ATTR bool fade_timercb(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_ctx);
static void iot_timer_start(gptimer_handle_t gptimer)
{
/* Select and initialize basic parameters of the timer */
timer_config_t config = {
.divider = HW_TIMER_DIVIDER,
.counter_dir = TIMER_COUNT_UP,
.counter_en = TIMER_PAUSE,
.alarm_en = TIMER_ALARM_EN,
.intr_type = TIMER_INTR_LEVEL,
.auto_reload = auto_reload,
gptimer_alarm_config_t alarm_config = {
.reload_count = 0,
.alarm_count = DUTY_SET_CYCLE / 1000 * GPTIMER_RESOLUTION_HZ,
.flags.auto_reload_on_alarm = true,
};
timer_init(timer_id->timer_group, timer_id->timer_id, &config);
/* Timer's counter will initially start from value below.
Also, if auto_reload is set, this value will be automatically reload on alarm */
timer_set_counter_value(timer_id->timer_group, timer_id->timer_id, 0x00000000ULL);
/* Configure the alarm value and the interrupt on alarm. */
timer_set_alarm_value(timer_id->timer_group, timer_id->timer_id, timer_interval_ms * HW_TIMER_SCALE / 1000);
timer_enable_intr(timer_id->timer_group, timer_id->timer_id);
timer_isr_register(timer_id->timer_group, timer_id->timer_id, isr_handle,
(void *) timer_id->timer_id, ESP_INTR_FLAG_IRAM, NULL);
}
static void iot_timer_start(hw_timer_idx_t *timer_id)
{
timer_start(timer_id->timer_group, timer_id->timer_id);
gptimer_event_callbacks_t cbs = {
.on_alarm = fade_timercb,
};
gptimer_register_event_callbacks(gptimer, &cbs, NULL);
gptimer_set_alarm_action(gptimer, &alarm_config);
gptimer_start(gptimer);
g_hw_timer_started = true;
}
static IRAM_ATTR void iot_timer_stop(hw_timer_idx_t *timer_id)
static IRAM_ATTR void iot_timer_stop(gptimer_handle_t gptimer)
{
timer_group_set_counter_enable_in_isr(timer_id->timer_group, timer_id->timer_id, TIMER_PAUSE);
gptimer_stop(gptimer);
g_hw_timer_started = false;
}
@ -265,18 +248,10 @@ static IRAM_ATTR uint32_t gamma_value_to_duty(int value)
return (cur + (next - cur) * tmp_r / (0x1U << LEDC_FIXED_Q));
}
static IRAM_ATTR void fade_timercb(void *para)
static IRAM_ATTR bool fade_timercb(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_ctx)
{
int timer_idx = (int) para;
int idle_channel_num = 0;
/* Retrieve the interrupt status */
timer_group_get_intr_status_in_isr(HW_TIMER_GROUP);
timer_group_clr_intr_status_in_isr(HW_TIMER_GROUP, timer_idx);
/* After the alarm has been triggered
we need enable it again, so it is triggered the next time */
timer_group_enable_alarm_in_isr(HW_TIMER_GROUP, timer_idx);
for (int channel = 0; channel < LEDC_CHANNEL_MAX; channel++) {
ledc_fade_data_t *fade_data = g_light_config->fade_data + channel;
@ -320,8 +295,10 @@ static IRAM_ATTR void fade_timercb(void *para)
}
if (idle_channel_num >= LEDC_CHANNEL_MAX) {
iot_timer_stop(&g_light_config->timer_id);
iot_timer_stop(timer);
}
return false;
}
esp_err_t iot_led_init(ledc_timer_t timer_num, ledc_mode_t speed_mode, uint32_t freq_hz)
@ -352,13 +329,12 @@ esp_err_t iot_led_init(ledc_timer_t timer_num, ledc_mode_t speed_mode, uint32_t
g_light_config->timer_num = timer_num;
g_light_config->speed_mode = speed_mode;
hw_timer_idx_t hw_timer = {
.timer_group = HW_TIMER_GROUP,
.timer_id = HW_TIMER_ID,
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_APB,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = GPTIMER_RESOLUTION_HZ,
};
g_light_config->timer_id = hw_timer;
iot_timer_create(&hw_timer, 1, DUTY_SET_CYCLE, fade_timercb);
ESP_ERROR_CHECK(gptimer_new_timer(&timer_config, &g_light_config->gptimer));
} else {
ESP_LOGE(TAG, "g_light_config has been initialized");
}
@ -372,12 +348,12 @@ esp_err_t iot_led_deinit(void)
free(g_gamma_table);
}
if (g_light_config) {
gptimer_del_timer(g_light_config->gptimer);
free(g_light_config);
}
timer_disable_intr(g_light_config->timer_id.timer_group, g_light_config->timer_id.timer_id);
return ESP_OK;
}
@ -449,7 +425,7 @@ esp_err_t iot_led_set_channel(ledc_channel_t channel, uint8_t value, uint32_t fa
}
if (g_hw_timer_started != true) {
iot_timer_start(&g_light_config->timer_id);
iot_timer_start(g_light_config->gptimer);
}
return ESP_OK;
@ -469,7 +445,7 @@ esp_err_t iot_led_start_blink(ledc_channel_t channel, uint8_t value, uint32_t pe
fade_data->step = (fade_flag) ? fade_data->cur / fade_data->num * -1 : 0;
if (g_hw_timer_started != true) {
iot_timer_start(&g_light_config->timer_id);
iot_timer_start(g_light_config->gptimer);
}
return ESP_OK;

View File

@ -1,12 +1,12 @@
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include "math.h"
#include "sys/time.h"
#include <math.h>
#include <sys/time.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/timers.h"
@ -14,7 +14,7 @@
#include "soc/ledc_reg.h"
#include "soc/timer_group_struct.h"
#include "soc/ledc_struct.h"
#include "driver/timer.h"
#include "driver/gptimer.h"
#include "driver/ledc.h"
#include "iot_light.h"
@ -27,6 +27,8 @@ static const char *TAG = "light";
#define POINT_ASSERT(tag, param) IOT_CHECK(tag, (param) != NULL, ESP_FAIL)
#define LIGHT_NUM_MAX 4
#define GPTIMER_RESOLUTION_HZ 1000000 // 1MHz, 1 tick=1us
typedef enum {
LIGHT_CH_NUM_1 = 1, /*!< Light channel number */
LIGHT_CH_NUM_2 = 2, /*!< Light channel number */
@ -36,11 +38,6 @@ typedef enum {
LIGHT_CH_NUM_MAX, /*!< user shouldn't use this */
} light_channel_num_t;
typedef struct {
timer_group_t timer_group;
timer_idx_t timer_id;
} hw_timer_idx_t;
typedef struct {
gpio_num_t io_num;
ledc_mode_t mode;
@ -62,8 +59,8 @@ typedef struct {
uint32_t full_duty;
uint32_t freq_hz;
ledc_timer_bit_t timer_bit;
hw_timer_idx_t hw_timer;
light_channel_t *channel_group[0];
gptimer_handle_t gptimer;
light_channel_t *channel_group[];
} light_t;
static bool g_fade_installed = false;
@ -71,43 +68,6 @@ static bool g_hw_timer_started = false;
static light_t *g_light_group[LIGHT_NUM_MAX] = {NULL};
static esp_err_t iot_light_duty_set(light_handle_t light_handle, uint8_t channel_id, uint32_t duty);
static void iot_timer_create(hw_timer_idx_t *timer_id, bool auto_reload, double timer_interval_sec, timer_isr_handle_t *isr_handle)
{
/* Select and initialize basic parameters of the timer */
timer_config_t config = {
.divider = HW_TIMER_DIVIDER,
.counter_dir = TIMER_COUNT_UP,
.counter_en = TIMER_PAUSE,
.alarm_en = TIMER_ALARM_EN,
.intr_type = TIMER_INTR_LEVEL,
.auto_reload = auto_reload,
};
timer_init(timer_id->timer_group, timer_id->timer_id, &config);
/* Timer's counter will initially start from value below.
Also, if auto_reload is set, this value will be automatically reload on alarm */
timer_set_counter_value(timer_id->timer_group, timer_id->timer_id, 0x00000000ULL);
/* Configure the alarm value and the interrupt on alarm. */
timer_set_alarm_value(timer_id->timer_group, timer_id->timer_id, timer_interval_sec * HW_TIMER_SCALE);
timer_enable_intr(timer_id->timer_group, timer_id->timer_id);
timer_isr_register(timer_id->timer_group, timer_id->timer_id, (void *)isr_handle,
(void *) timer_id->timer_id, ESP_INTR_FLAG_IRAM, NULL);
}
static void iot_timer_start(hw_timer_idx_t *timer_id)
{
timer_start(timer_id->timer_group, timer_id->timer_id);
g_hw_timer_started = true;
}
static void iot_timer_stop(hw_timer_idx_t *timer_id)
{
timer_disable_intr(timer_id->timer_group, timer_id->timer_id);
timer_pause(timer_id->timer_group, timer_id->timer_id);
g_hw_timer_started = false;
}
static IRAM_ATTR void iot_ledc_ls_channel_update(ledc_mode_t speed_mode, ledc_channel_t channel_num)
{
if (speed_mode == LEDC_LOW_SPEED_MODE) {
@ -155,17 +115,8 @@ static IRAM_ATTR esp_err_t iot_ledc_update_duty(ledc_mode_t speed_mode, ledc_cha
return ESP_OK;
}
static IRAM_ATTR void breath_timer_callback(void *para)
static IRAM_ATTR bool breath_timer_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_ctx)
{
int timer_idx = (int) para;
/* Retrieve the interrupt status */
timer_group_get_intr_status_in_isr(HW_TIMER_GROUP);
timer_group_clr_intr_status_in_isr(HW_TIMER_GROUP, timer_idx);
/* After the alarm has been triggered
we need enable it again, so it is triggered the next time */
timer_group_enable_alarm_in_isr(HW_TIMER_GROUP, timer_idx);
for (int i = 0; i < LIGHT_NUM_MAX; i++) {
if (g_light_group[i] != NULL) {
light_t *light = g_light_group[i];
@ -194,6 +145,7 @@ static IRAM_ATTR void breath_timer_callback(void *para)
}
}
}
return false;
}
static light_channel_t *light_channel_create(gpio_num_t io_num, ledc_channel_t channel, ledc_mode_t mode, ledc_timer_t timer)
@ -268,12 +220,26 @@ light_handle_t iot_light_create(ledc_timer_t timer, ledc_mode_t speed_mode, uint
light_ptr->freq_hz = freq_hz;
light_ptr->mode = speed_mode;
light_ptr->timer_bit = timer_bit;
light_ptr->hw_timer.timer_group = HW_TIMER_GROUP;
light_ptr->hw_timer.timer_id = HW_TIMER_ID;
if (g_hw_timer_started == false) {
iot_timer_create(&(light_ptr->hw_timer), 1, (double)DUTY_SET_CYCLE / 1000, (void *)breath_timer_callback);
iot_timer_start(&(light_ptr->hw_timer));
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_APB,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = GPTIMER_RESOLUTION_HZ,
};
ESP_ERROR_CHECK(gptimer_new_timer(&timer_config, &light_ptr->gptimer));
gptimer_alarm_config_t alarm_config = {
.alarm_count = DUTY_SET_CYCLE / 1000 * GPTIMER_RESOLUTION_HZ,
.reload_count = 0,
.flags.auto_reload_on_alarm = true,
};
gptimer_event_callbacks_t cbs = {
.on_alarm = breath_timer_callback,
};
gptimer_register_event_callbacks(light_ptr->gptimer, &cbs, NULL);
gptimer_set_alarm_action(light_ptr->gptimer, &alarm_config);
gptimer_start(light_ptr->gptimer);
g_hw_timer_started = true;
}
for (int i = 0; i < channel_num; i++) {
@ -317,7 +283,9 @@ esp_err_t iot_light_delete(light_handle_t light_handle)
ledc_fade_func_uninstall();
g_fade_installed = false;
iot_timer_stop(&(light->hw_timer));
g_hw_timer_started = false;
gptimer_stop(light->gptimer);
gptimer_del_timer(light->gptimer);
FREE_MEM:
free(light_handle);
return ESP_OK;

View File

@ -2,7 +2,7 @@
# in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
set(EXTRA_COMPONENT_DIRS "$ENV{IDF_PATH}/examples/common_components"
set(EXTRA_COMPONENT_DIRS "$ENV{IDF_PATH}/examples/common_components/pid_ctrl"
"$ENV{IDF_PATH}/examples/peripherals/pcnt/rotary_encoder/components")
include($ENV{IDF_PATH}/tools/cmake/project.cmake)

View File

@ -0,0 +1,112 @@
| Supported Targets | ESP32 | ESP32-S3 |
| ----------------- | ----- | -------- |
# MCPWM Brushed DC Motor Example
(See the README.md file in the upper level 'examples' directory for more information about examples.)
This example mainly illustrates how to drive a brushed DC motor by generating two specific PWM signals. However the PWM signals from ESP32 can't drive motors directly as the motor usually consumes high current. So an H-bridge like [DRV8848](https://www.ti.com/product/DRV8848) should be used to provide the needed voltage and current for brushed DC motor. To measure the speed of motor, a photoelectric encoder is used to generate the "speed feedback" signals (e.g. a pair of quadrature signal). The example uses a simple PID control approach to keep the motor speed in a constant speed. The example provides a console command line interface for user to update the PID parameters according to actual situation.
## How to Use Example
Before project configuration and build, be sure to set the correct chip target using `idf.py set-target <chip_name>`.
### Hardware Required
* A development board with any Espressif SoC which features MCPWM and PCNT peripheral (e.g., ESP32-DevKitC, ESP-WROVER-KIT, etc.)
* A USB cable for Power supply and programming
* A separate 12V power supply for brushed DC motor and H-bridge (the voltage depends on the motor model used in the example)
* A motor driving board to transfer pwm signal into driving signal
* A brushed DC motor, e.g. [25GA370](http://www.tronsunmotor.com/data/upload/file/201807/e03b98802b5c5390d6570939def525ba.pdf)
* A quadrature encoder to detect speed
Connection :
```
Power(12V)
|
v
+----------------+ +--------------------+
| | | H-Bridge |
| GND +<----------->| GND | +--------------+
| | | | | |
| GENA_GPIO_NUM +----PWM0A--->| IN_A OUT_A +----->| Brushed |
| | | | | DC |
| GENB_GPIO_NUM +----PWM0B--->| IN_B OUT_B +----->| Motor |
| | | | | |
| ESP | +--------------------+ | |
| | +------+-------+
| | |
| | +--------------------+ |
| VCC3.3 +------------>| VCC Encoder | |
| | | | |
| GND +<----------->| |<------------+
| | | |
|PHASEA_GPIO_NUM |<---PhaseA---+ C1 |
| | | |
|PHASEB_GPIO_NUM |<---PhaseB---+ C2 |
| | | |
+----------------+ +--------------------+
```
### Build and Flash
Run `idf.py -p PORT flash monitor` to build, flash and monitor the project.
(To exit the serial monitor, type ``Ctrl-]``.)
See the [Getting Started Guide](https://idf.espressif.com/) for full steps to configure and use ESP-IDF to build projects.
## Example Output
Run the example, you will see the following output log:
```
I (0) cpu_start: Starting scheduler on APP CPU.
configure mcpwm gpio
init mcpwm driver
init and start rotary encoder
init PID control block
init motor control timer
D (561) gptimer: new group (0) @0x3fce0a24
D (561) gptimer: new gptimer (0,0) at 0x3fce0964, resolution=1000000Hz
create motor control task
start motor control timer
D (571) gptimer: install interrupt service for timer (0,0)
install console command line
Type 'help' to get the list of commands.
Use UP/DOWN arrows to navigate through command history.
Press TAB when typing command name to auto-complete.
dc-motor>
dc-motor> help
help
Print the list of registered commands
pid [-p <kp>] [-i <ki>] [-d <kd>]
Set PID parameters
-p <kp> Set Kp value of PID
-i <ki> Set Ki value of PID
-d <kd> Set Kd value of PID
```
### Set PID parameters
* Command: `pid -p <double> -i <double> -d <double> -t <loc/inc>`
* 'p' - proportion value
* 'i' - integral value
* 'd' - differential value
* 't' - PID calculation type (locational or incremental).
```bash
mcpwm-motor> pid -p 0.8 -i 0.02 -d 0.1 -t inc
pid: kp = 0.800
pid: ki = 0.020
pid: kd = 0.100
pid: type = increment
```
## Troubleshooting
* Make sure your ESP board and H-bridge module have been connected to the same GND panel.
For any technical queries, please open an [issue](https://github.com/espressif/esp-idf/issues) on GitHub. We will get back to you soon.

View File

@ -0,0 +1,2 @@
idf_component_register(SRCS "mcpwm_bdc_control_example_main.c"
INCLUDE_DIRS ".")

View File

@ -0,0 +1,232 @@
/*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "driver/gptimer.h"
#include "driver/mcpwm.h"
#include "rotary_encoder.h"
#include "pid_ctrl.h"
#include "esp_console.h"
#include "argtable3/argtable3.h"
// Enable this config, we will print debug formated string, which in return can be captured and parsed by Serial-Studio
#define SERIAL_STUDIO_DEBUG 0
#define BDC_MCPWM_UNIT 0
#define BDC_MCPWM_TIMER 0
#define BDC_MCPWM_GENA_GPIO_NUM 7
#define BDC_MCPWM_GENB_GPIO_NUM 15
#define BDC_MCPWM_FREQ_HZ 1500
#define BDC_ENCODER_PCNT_UNIT 0
#define BDC_ENCODER_PHASEA_GPIO_NUM 36
#define BDC_ENCODER_PHASEB_GPIO_NUM 35
#define BDC_PID_CALCULATION_PERIOD_US 10000
#define BDC_PID_FEEDBACK_QUEUE_LEN 10
static pid_ctrl_parameter_t pid_runtime_param = {
.kp = 0.6,
.ki = 0.3,
.kd = 0.12,
.cal_type = PID_CAL_TYPE_INCREMENTAL,
.max_output = 100,
.min_output = -100,
.max_integral = 1000,
.min_integral = -1000,
};
static bool pid_need_update = false;
static int expect_pulses = 300;
static int real_pulses;
typedef struct {
rotary_encoder_t *encoder;
QueueHandle_t pid_feedback_queue;
} motor_control_timer_context_t;
typedef struct {
QueueHandle_t pid_feedback_queue;
pid_ctrl_block_handle_t pid_ctrl;
} motor_control_task_context_t;
static void brushed_motor_set_duty(float duty_cycle)
{
/* motor moves in forward direction, with duty cycle = duty % */
if (duty_cycle > 0) {
mcpwm_set_signal_low(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_A);
mcpwm_set_duty(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_B, duty_cycle);
mcpwm_set_duty_type(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_B, MCPWM_DUTY_MODE_0);
}
/* motor moves in backward direction, with duty cycle = -duty % */
else {
mcpwm_set_signal_low(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_B);
mcpwm_set_duty(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_A, -duty_cycle);
mcpwm_set_duty_type(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, MCPWM_OPR_A, MCPWM_DUTY_MODE_0);
}
}
static bool motor_ctrl_timer_cb(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *arg)
{
static int last_pulse_count = 0;
BaseType_t high_task_awoken = pdFALSE;
motor_control_timer_context_t *user_ctx = (motor_control_timer_context_t *)arg;
rotary_encoder_t *encoder = user_ctx->encoder;
int cur_pulse_count = encoder->get_counter_value(encoder);
int delta = cur_pulse_count - last_pulse_count;
last_pulse_count = cur_pulse_count;
xQueueSendFromISR(user_ctx->pid_feedback_queue, &delta, &high_task_awoken);
return high_task_awoken == pdTRUE;
}
static void bdc_ctrl_task(void *arg)
{
float duty_cycle = 0;
motor_control_task_context_t *user_ctx = (motor_control_task_context_t *)arg;
while (1) {
xQueueReceive(user_ctx->pid_feedback_queue, &real_pulses, portMAX_DELAY);
float error = expect_pulses - real_pulses;
pid_compute(user_ctx->pid_ctrl, error, &duty_cycle);
brushed_motor_set_duty(duty_cycle);
}
}
static struct {
struct arg_dbl *kp;
struct arg_dbl *ki;
struct arg_dbl *kd;
struct arg_end *end;
} pid_ctrl_args;
static int do_pid_ctrl_cmd(int argc, char **argv)
{
int nerrors = arg_parse(argc, argv, (void **)&pid_ctrl_args);
if (nerrors != 0) {
arg_print_errors(stderr, pid_ctrl_args.end, argv[0]);
return 0;
}
if (pid_ctrl_args.kp->count) {
pid_runtime_param.kp = pid_ctrl_args.kp->dval[0];
}
if (pid_ctrl_args.ki->count) {
pid_runtime_param.ki = pid_ctrl_args.ki->dval[0];
}
if (pid_ctrl_args.kd->count) {
pid_runtime_param.kd = pid_ctrl_args.kd->dval[0];
}
pid_need_update = true;
return 0;
}
static void register_pid_console_command(void)
{
pid_ctrl_args.kp = arg_dbl0("p", NULL, "<kp>", "Set Kp value of PID");
pid_ctrl_args.ki = arg_dbl0("i", NULL, "<ki>", "Set Ki value of PID");
pid_ctrl_args.kd = arg_dbl0("d", NULL, "<kd>", "Set Kd value of PID");
pid_ctrl_args.end = arg_end(2);
const esp_console_cmd_t pid_ctrl_cmd = {
.command = "pid",
.help = "Set PID parameters",
.hint = NULL,
.func = &do_pid_ctrl_cmd,
.argtable = &pid_ctrl_args
};
ESP_ERROR_CHECK(esp_console_cmd_register(&pid_ctrl_cmd));
}
void app_main(void)
{
QueueHandle_t pid_fb_queue = xQueueCreate(BDC_PID_FEEDBACK_QUEUE_LEN, sizeof(int));
assert(pid_fb_queue);
printf("configure mcpwm gpio\r\n");
ESP_ERROR_CHECK(mcpwm_gpio_init(BDC_MCPWM_UNIT, MCPWM0A, BDC_MCPWM_GENA_GPIO_NUM));
ESP_ERROR_CHECK(mcpwm_gpio_init(BDC_MCPWM_UNIT, MCPWM0B, BDC_MCPWM_GENB_GPIO_NUM));
printf("init mcpwm driver\n");
mcpwm_config_t pwm_config = {
.frequency = BDC_MCPWM_FREQ_HZ,
.cmpr_a = 0,
.cmpr_b = 0,
.counter_mode = MCPWM_UP_COUNTER,
.duty_mode = MCPWM_DUTY_MODE_0,
};
ESP_ERROR_CHECK(mcpwm_init(BDC_MCPWM_UNIT, BDC_MCPWM_TIMER, &pwm_config));
printf("init and start rotary encoder\r\n");
rotary_encoder_config_t config = {
.dev = (rotary_encoder_dev_t)BDC_ENCODER_PCNT_UNIT,
.phase_a_gpio_num = BDC_ENCODER_PHASEA_GPIO_NUM,
.phase_b_gpio_num = BDC_ENCODER_PHASEB_GPIO_NUM,
};
rotary_encoder_t *speed_encoder = NULL;
ESP_ERROR_CHECK(rotary_encoder_new_ec11(&config, &speed_encoder));
ESP_ERROR_CHECK(speed_encoder->set_glitch_filter(speed_encoder, 1));
ESP_ERROR_CHECK(speed_encoder->start(speed_encoder));
printf("init PID control block\r\n");
pid_ctrl_block_handle_t pid_ctrl;
pid_ctrl_config_t pid_config = {
.init_param = pid_runtime_param,
};
ESP_ERROR_CHECK(pid_new_control_block(&pid_config, &pid_ctrl));
printf("init motor control timer\r\n");
gptimer_handle_t gptimer;
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_APB,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = 1000000, // 1MHz, 1 tick = 1us
};
ESP_ERROR_CHECK(gptimer_new_timer(&timer_config, &gptimer));
printf("create motor control task\r\n");
static motor_control_task_context_t my_ctrl_task_ctx = {};
my_ctrl_task_ctx.pid_feedback_queue = pid_fb_queue;
my_ctrl_task_ctx.pid_ctrl = pid_ctrl;
xTaskCreate(bdc_ctrl_task, "bdc_ctrl_task", 4096, &my_ctrl_task_ctx, 5, NULL);
printf("start motor control timer\r\n");
static motor_control_timer_context_t my_timer_ctx = {};
my_timer_ctx.pid_feedback_queue = pid_fb_queue;
my_timer_ctx.encoder = speed_encoder;
gptimer_event_callbacks_t cbs = {
.on_alarm = motor_ctrl_timer_cb,
};
ESP_ERROR_CHECK(gptimer_register_event_callbacks(gptimer, &cbs, &my_timer_ctx));
gptimer_alarm_config_t alarm_config = {
.reload_count = 0,
.alarm_count = BDC_PID_CALCULATION_PERIOD_US,
.flags.auto_reload_on_alarm = true,
};
ESP_ERROR_CHECK(gptimer_set_alarm_action(gptimer, &alarm_config));
ESP_ERROR_CHECK(gptimer_start(gptimer));
printf("install console command line\r\n");
esp_console_repl_t *repl = NULL;
esp_console_repl_config_t repl_config = ESP_CONSOLE_REPL_CONFIG_DEFAULT();
repl_config.prompt = "dc-motor>";
esp_console_dev_uart_config_t uart_config = ESP_CONSOLE_DEV_UART_CONFIG_DEFAULT();
ESP_ERROR_CHECK(esp_console_new_repl_uart(&uart_config, &repl_config, &repl));
register_pid_console_command();
ESP_ERROR_CHECK(esp_console_start_repl(repl));
while (1) {
vTaskDelay(pdMS_TO_TICKS(100));
// the following logging format is according to the requirement of serial-studio
// also see the parser mapping file `serial-studio-proto-map.json` in the project folder
#if SERIAL_STUDIO_DEBUG
printf("/*%d*/\r\n", real_pulses);
#endif
if (pid_need_update) {
pid_update_parameters(pid_ctrl, &pid_runtime_param);
pid_need_update = false;
}
}
}

View File

@ -0,0 +1,22 @@
{
"fe": "*/",
"fs": "/*",
"g": [
{
"d": [
{
"g": true,
"max": 100,
"min": 0,
"t": "pulses within 10ms",
"u": "",
"v": "%1",
"w": ""
}
],
"t": "Encoder Feedback",
}
],
"s": ",",
"t": "Brushed DC Motor Speed"
}

View File

@ -1,246 +0,0 @@
| Supported Targets | ESP32 | ESP32-S3 |
| ----------------- | ----- | -------- |
# MCPWM Brushed DC Motor Example
(See the README.md file in the upper level 'examples' directory for more information about examples.)
This example mainly illustrates how to drive a brushed DC motor by generating two specific PWM signals. This example assumes an [L298N](https://www.st.com/content/st_com/en/products/motor-drivers/brushed-dc-motor-drivers/l298.html) H-bridge driver is used to provide the needed voltage and current for brushed DC motor. This example also implements a motor control command console such that users can configure and control the motors at run time using console commands.
## How to Use Example
Before project configuration and build, be sure to set the correct chip target using `idf.py set-target <chip_name>`.
### Hardware Required
* A development board with any Espressif SoC which features MCPWM and PCNT peripheral (e.g., ESP32-DevKitC, ESP-WROVER-KIT, etc.)
* A USB cable for Power supply and programming
* A separate 12V power supply for brushed DC motor and H-bridge (the voltage depends on the motor model used in the example)
* A motor driving board to transfer pwm signal into driving signal
* A brushed DC motor, e.g. [25GA370](http://www.tronsunmotor.com/data/upload/file/201807/e03b98802b5c5390d6570939def525ba.pdf)
* A quadrature encoder to detect speed
Connection :
```
Power(12V)
|
v
+----------------+ +--------------------+
| | | H-Bridge |
| GND +------------>| | +--------------+
| | | | | |
| GPIO15 +----PWM0A--->| IN_A OUT_A +----->| Brushed |
| | | | | DC |
| GPIO16 +----PWM0B--->| IN_A OUT_B +----->| Motor |
| | | | | |
| ESP | +--------------------+ | |
| | +------+-------+
| | |
| | +--------------------+ |
| VCC3.3 +------------>| Encoder | |
| | | | |
| GND +------------>| |<------------+
| | | |
| GPIO18 |<---PhaseA---+ C1 |
| | | |
| GPIO19 |<---PhaseB---+ C2 |
| | | |
+----------------+ +--------------------+
```
NOTE: If some other GPIO pins (e.g., 13/14) are chosen as the PCNT encoder pins, flashing might fail while the wires are connected. If this occurs, please try disconnecting the power supply of the encoder while flashing.
### Build and Flash
Run `idf.py -p PORT flash monitor` to build, flash and monitor the project.
(To exit the serial monitor, type ``Ctrl-]``.)
See the [Getting Started Guide](https://idf.espressif.com/) for full steps to configure and use ESP-IDF to build projects.
## Example Output
Run the example, you will see the following output log:
```bash
...
Testing brushed motor with PID...
initializing mcpwm gpio...
Configuring Initial Parameters of mcpwm...
Type 'help' to get the list of commands.
Use UP/DOWN arrows to navigate through command history.
Press TAB when typing command name to auto-complete.
=================================================================
| Example of Motor Control |
| |
| 1. Try 'help', check all supported commands |
| 2. Try 'config' to set control period or pwm frequency |
| 3. Try 'pid' to configure pid paremeters |
| 4. Try 'expt' to set expectation value and mode |
| 5. Try 'motor' to start motor in several seconds or stop it |
| |
=================================================================
Default configuration are shown as follows.
You can input 'config -s' to check current status.
-----------------------------------------------------------------
Current Configuration Status
Configuration
Period = 10 ms PID = enabled
PID - Increment
Kp = 0.800 Ki = 0.000 Kd = 0.100
Expectation - Triangle
init = 30.000 max = 50.000 min = -50.000 pace = 1.000
MCPWM
Frequency = 1000 Hz
Motor
Running seconds = 10
-----------------------------------------------------------------
mcpwm-motor>
```
### Check all supported commands and their usages
* Command: `help`
```bash
mcpwm-motor> help
help
Print the list of registered commands
config config -s
Enable or disable PID and set motor control period
--pid=<y|n> Enable or disable PID algorithm
-T, --period=<ms> Set motor control period
-s, --show Show current configurations
expt expt -i <duty> -m <fixed/tri/rect> -p <double> --max <duty> --min -50<duty>
Set initial value, limitation and wave mode of expectation. Both dynamic and
static mode are available
--max=<duty> Max limitation for dynamic expectation
--min=<duty> Min limitation for dynamic expectation
-p, --pace=<double> The increasing pace of expectation every 50ms
-i, --init=<duty> Initial expectation. Usually between -100~100
-m, --mode=<fixed/tri/rect> Select static or dynamic expectation wave mode. 'fixed' for static, 'tri' for triangle, 'rect' for rectangle
pid pid -p <double> -i <double> -d <double> -t <loc/inc>
Set parameters and type for PID algorithm
-p, --kp=<double> Set Kp value for PID
-i, --ki=<double> Set Ki value for PID
-d, --kd=<double> Set Kd value for PID
-t, --type=<loc/inc> Select locational PID or incremental PID
motor motor -u 10
Start or stop the motor
-u, --start=<seconds> Set running seconds for motor, set '0' to keep motor running
-d, --stop Stop the motor
```
### Check status
* Command: `config -s`
```bash
mcpwm-motor> config -s
-----------------------------------------------------------------
Current Configuration Status
Configuration
Period = 10 ms PID = enabled
PID - Increment
Kp = 0.800 Ki = 0.000 Kd = 0.100
Expectation - Triangle
init = 30.000 max = 50.000 min = -50.000 pace = -1.000
MCPWM
Frequency = 1000 Hz
Motor
Running seconds = 10
-----------------------------------------------------------------
```
### Enable or disable PID
* Command: `config --pid <y/n>`
* 'y' - enable PID
* 'n' - disable PID
```bash
mcpwm-motor> config --pid n
config: pid disabled
mcpwm-motor> config --pid y
config: pid enabled
```
### Set PID parameters
* Command: `pid -p <double> -i <double> -d <double> -t <loc/inc>`
* 'p' - proportion value
* 'i' - integral value
* 'd' - differential value
* 't' - PID calculation type (locational or incremental).
```bash
mcpwm-motor> pid -p 0.8 -i 0.02 -d 0.1 -t inc
pid: kp = 0.800
pid: ki = 0.020
pid: kd = 0.100
pid: type = increment
```
### Set expectation parameters
* Command: `expt -i <duty> -m <fixed/tri/rect> -p <double> --max <duty> --min <duty>`
* 'i' - initial duty if you set mode 'fixed'
* 'm' - expectation mode. 'fixed' means the expectation will never change, 'tri' means the expectation will changes with trigonometric wave, 'rect' means the expectation will changes with rectangular wave
* 'p' - the setp size of expectation changed in every 50ms, it can adjust the expectation changing speed
* 'max' - the maximum limitation of expectation
* 'min' - the minimum limitation of expectation
```bash
mcpwm-motor> expt -i 40 -m rect -p 1.5 --max 80 --min -60
expt: init = 40.000
expt: max = 80.000
expt: min = -60.000
expt: pace = 1.500
expt: mode = rectangle
```
### Start or stop motor
* Command: `motor -u <sec>`
* Command: `motor -d`
* 'u' - start the motor in <sec> seconds, if <sec> is 0, the motor won't stop until 'motor -d' is inputed
* 'd' - stop the motor right now
```bash
mcpwm-motor> motor -u 10
motor: motor starts to run in 10 seconds
mcpwm-motor> 1
2
3
4
5
6
7
8
9
10
Time up: motor stoped
```
## Troubleshooting
* Make sure your ESP board and H-bridge module have been connected to the same GND panel.
For any technical queries, please open an [issue](https://github.com/espressif/esp-idf/issues) on GitHub. We will get back to you soon.

View File

@ -1,5 +0,0 @@
set(COMPONENT_SRCS "motor_ctrl_timer.c")
idf_component_register(SRCS "${COMPONENT_SRCS}"
INCLUDE_DIRS .
PRIV_REQUIRES "driver")

View File

@ -1,141 +0,0 @@
/* To set the control period for DC motor Timer
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include "motor_ctrl_timer.h"
#include "esp_check.h"
#define MOTOR_CTRL_TIMER_DIVIDER (16) // Hardware timer clock divider
#define MOTOR_CTRL_TIMER_SCALE (TIMER_BASE_CLK / MOTOR_CTRL_TIMER_DIVIDER) // convert counter value to seconds
#define MOTOR_CONTROL_TIMER_GROUP TIMER_GROUP_0
#define MOTOR_CONTROL_TIMER_ID TIMER_0
static const char *TAG = "motor_ctrl_timer";
/**
* @brief Callback function of timer intterupt
*
* @param args The parameter transmited to callback function from timer_isr_callback_add. Args here is for timer_info.
* @return
* - True Do task yield at the end of ISR
* - False Not do task yield at the end of ISR
*/
static bool IRAM_ATTR motor_ctrl_timer_isr_callback(void *args)
{
BaseType_t high_task_awoken = pdFALSE;
motor_ctrl_timer_info_t *info = (motor_ctrl_timer_info_t *) args;
info->pulse_info.pulse_cnt = info->pulse_info.get_pulse_callback(info->pulse_info.callback_args);
/* Now just send the event data back to the main program task */
xQueueSendFromISR(info->timer_evt_que, info, &high_task_awoken);
return high_task_awoken == pdTRUE; // return whether we need to yield at the end of ISR
}
/**
* @brief Initialize the motor control timer
*
* @param timer_info the secondary pointer of motor_ctrl_timer_info_t
* @param evt_que timer event queue
* @param ctrl_period_ms motor control period
* @param pulse_info quadrature encoder pulse information
* @return
* - ESP_OK: Motor control timer initialized successfully
* - ESP_FAIL: motor control timer failed to initialize because of other errors
*/
esp_err_t motor_ctrl_new_timer(motor_ctrl_timer_info_t **timer_info,
QueueHandle_t evt_que,
unsigned int ctrl_period_ms,
pulse_info_t pulse_info)
{
esp_err_t ret = ESP_FAIL;
/* Select and initialize basic parameters of the timer */
timer_config_t config = {
.divider = MOTOR_CTRL_TIMER_DIVIDER,
.counter_dir = TIMER_COUNT_UP,
.counter_en = TIMER_PAUSE,
.alarm_en = TIMER_ALARM_EN,
.auto_reload = true,
}; // default clock source is APB
ret = timer_init(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, &config);
ESP_RETURN_ON_ERROR(ret, TAG, "timer init failed\n");
/* Timer's counter will initially start from value below.
Since auto_reload is set, this value will be automatically reload on alarm */
timer_set_counter_value(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, 0);
/* Configure the alarm value and the interrupt on alarm. */
timer_set_alarm_value(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, ctrl_period_ms * MOTOR_CTRL_TIMER_SCALE / 1000);
timer_enable_intr(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID);
/* Check the pointers */
ESP_GOTO_ON_FALSE(evt_que, ESP_ERR_INVALID_ARG, err, TAG, "timer event queue handler is NULL\n");
ESP_GOTO_ON_FALSE(timer_info, ESP_ERR_INVALID_ARG, err, TAG, "timer info structure pointer is NULL\n");
/* Alloc and config the infomation structure for this file */
*timer_info = calloc(1, sizeof(motor_ctrl_timer_info_t));
ESP_GOTO_ON_FALSE(*timer_info, ESP_ERR_NO_MEM, err, TAG, "timer_info calloc failed\n");
(*timer_info)->timer_group = MOTOR_CONTROL_TIMER_GROUP;
(*timer_info)->timer_idx = MOTOR_CONTROL_TIMER_ID;
(*timer_info)->timer_evt_que = evt_que;
(*timer_info)->ctrl_period_ms = ctrl_period_ms;
(*timer_info)->pulse_info = pulse_info;
timer_isr_callback_add(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, motor_ctrl_timer_isr_callback, *timer_info, 0);
return ret;
err:
timer_deinit(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID);
return ret;
}
/**
* @brief Set timer alarm period
*
* @param period Timer alarm period
* @return
* - void
*/
void motor_ctrl_timer_set_period(unsigned int period)
{
timer_set_alarm_value(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, period * MOTOR_CTRL_TIMER_SCALE / 1000);
}
/**
* @brief Start the timer
*/
void motor_ctrl_timer_start(void)
{
/* start the timer */
timer_start(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID);
}
/**
* @brief Pause the timer and clear the counting value
*/
void motor_ctrl_timer_stop(void)
{
/* stop the timer */
timer_pause(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID);
timer_set_counter_value(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID, 0);
}
/**
* @brief Deinitialize the timer
*
* @param timer_info the secondary pointer of motor_ctrl_timer_info_t, the memory will be freed
*/
void motor_ctrl_timer_deinit(motor_ctrl_timer_info_t **timer_info)
{
if (*timer_info != NULL) {
timer_deinit(MOTOR_CONTROL_TIMER_GROUP, MOTOR_CONTROL_TIMER_ID);
free(*timer_info);
*timer_info = NULL;
}
}

View File

@ -1,78 +0,0 @@
/* To set the control period for DC motor Timer
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "driver/timer.h"
typedef struct {
int (*get_pulse_callback)(void *);
void *callback_args;
int pulse_cnt;
} pulse_info_t;
typedef struct {
timer_group_t timer_group; /* Timer Group number */
timer_idx_t timer_idx; /* Timer ID */
unsigned int ctrl_period_ms; /* Motor control period, unit in ms */
QueueHandle_t timer_evt_que; /* The queue of timer events */
pulse_info_t pulse_info;
} motor_ctrl_timer_info_t;
/**
* @brief Initialize the motor control timer
*
* @param timer_info the secondary pointer of motor_ctrl_timer_info_t
* @param evt_que timer event queue
* @param ctrl_period_ms motor control period
* @param pulse_info quadrature encoder pulse information
* @return
* - ESP_OK: Motor control timer initialized successfully
* - ESP_FAIL: motor control timer failed to initialize because of other errors
*/
esp_err_t motor_ctrl_new_timer(motor_ctrl_timer_info_t **timer_info,
QueueHandle_t evt_que,
unsigned int ctrl_period_ms,
pulse_info_t pulse_info);
/**
* @brief Set timer alarm period
*
* @param period Timer alarm period
*/
void motor_ctrl_timer_set_period(unsigned int period);
/**
* @brief Start the timer
*/
void motor_ctrl_timer_start(void);
/**
* @brief Pause the timer and clear the counting value
*/
void motor_ctrl_timer_stop(void);
/**
* @brief Deinitialize the timer
*
* @param timer_info the secondary pointer of motor_ctrl_timer_info_t, the memory will be freed
*/
void motor_ctrl_timer_deinit(motor_ctrl_timer_info_t **timer_info);
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +0,0 @@
set(COMPONENT_SRCS "mcpwm_brushed_dc_control_example.c"
"cmd_mcpwm_motor.c")
idf_component_register(SRCS "${COMPONENT_SRCS}"
INCLUDE_DIRS "./")

View File

@ -1,308 +0,0 @@
/* cmd_mcpwm_motor.h
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "argtable3/argtable3.h"
#include "esp_console.h"
#include "esp_log.h"
#include "mcpwm_brushed_dc_control_example.h"
#define MOTOR_CTRL_CMD_CHECK(ins) if(arg_parse(argc, argv, (void **)&ins)){ \
arg_print_errors(stderr, ins.end, argv[0]); \
return 0;}
static mcpwm_motor_control_t *mc;
extern SemaphoreHandle_t g_motor_mux;
static struct {
struct arg_str *pid_flag;
struct arg_int *period;
struct arg_lit *show;
struct arg_end *end;
} motor_ctrl_config_args;
static struct {
struct arg_dbl *max;
struct arg_dbl *min;
struct arg_dbl *pace;
struct arg_dbl *init;
struct arg_str *mode;
struct arg_end *end;
} motor_ctrl_expt_args;
static struct {
struct arg_dbl *kp;
struct arg_dbl *ki;
struct arg_dbl *kd;
struct arg_str *type;
struct arg_end *end;
} motor_ctrl_pid_args;
static struct {
struct arg_int *start;
struct arg_lit *stop;
struct arg_end *end;
} motor_ctrl_motor_args;
static void print_current_status(void)
{
printf("\n -----------------------------------------------------------------\n");
printf(" Current Configuration Status \n\n");
printf(" Configuration\n Period = %d ms\tPID = %s\n\n",
mc->cfg.ctrl_period, mc->cfg.pid_enable ? "enabled" : "disabled");
printf(" PID - %s\n Kp = %.3f\tKi = %.3f\tKd = %.3f\n\n",
(mc->pid_param.cal_type == PID_CAL_TYPE_POSITIONAL) ? "Location" : "Increment",
mc->pid_param.kp, mc->pid_param.ki, mc->pid_param.kd);
printf(" Expectation - %s\n init = %.3f\tmax = %.3f\tmin = %.3f\tpace = %.3f\n\n",
mc->cfg.expt_mode ? (mc->cfg.expt_mode == MOTOR_CTRL_MODE_TRIANGLE ? "Triangle" : "Rectangle") : "Fixed",
mc->cfg.expt_init, mc->cfg.expt_max, mc->cfg.expt_min, mc->cfg.expt_pace);
printf(" MCPWM\n Frequency = %d Hz\n\n", mc->cfg.pwm_freq);
printf(" Motor\n Running seconds = %d\n", mc->cfg.running_sec);
printf(" -----------------------------------------------------------------\n\n");
}
static int do_motor_ctrl_config_cmd(int argc, char **argv)
{
MOTOR_CTRL_CMD_CHECK(motor_ctrl_config_args);
xSemaphoreTake(g_motor_mux, portMAX_DELAY);
if (motor_ctrl_config_args.pid_flag->count) {
if (!strcmp(*motor_ctrl_config_args.pid_flag->sval, "n") ||
!strcmp(*motor_ctrl_config_args.pid_flag->sval, "no")) {
mc->cfg.pid_enable = false;
printf("config: pid disabled\n");
} else {
mc->cfg.pid_enable = true;
printf("config: pid enabled\n");
}
}
if (motor_ctrl_config_args.period->count) {
mc->cfg.ctrl_period = motor_ctrl_config_args.period->ival[0];
motor_ctrl_timer_set_period(mc->cfg.ctrl_period);
printf("config: control period = mc->cfg.ctrl_period\n");
}
if (motor_ctrl_config_args.show->count) {
print_current_status();
}
xSemaphoreGive(g_motor_mux);
return 0;
}
static int do_motor_ctrl_expt_cmd(int argc, char **argv)
{
MOTOR_CTRL_CMD_CHECK(motor_ctrl_expt_args);
xSemaphoreTake(g_motor_mux, portMAX_DELAY);
if (motor_ctrl_expt_args.init->count) {
mc->cfg.expt_init = motor_ctrl_expt_args.init->dval[0];
printf("expt: init = %.3f\n", mc->cfg.expt_init);
}
if (motor_ctrl_expt_args.max->count) {
mc->cfg.expt_max = motor_ctrl_expt_args.max->dval[0];
printf("expt: max = %.3f\n", mc->cfg.expt_max);
}
if (motor_ctrl_expt_args.min->count) {
mc->cfg.expt_min = motor_ctrl_expt_args.min->dval[0];
printf("expt: min = %.3f\n", mc->cfg.expt_min);
}
if (motor_ctrl_expt_args.pace->count) {
mc->cfg.expt_pace = motor_ctrl_expt_args.pace->dval[0];
printf("expt: pace = %.3f\n", mc->cfg.expt_pace);
}
if (motor_ctrl_expt_args.mode->count) {
if (!strcmp(*motor_ctrl_expt_args.mode->sval, "fixed")) {
mc->cfg.expt_mode = MOTOR_CTRL_MODE_FIXED;
printf("expt: mode = fixed\n");
} else if (!strcmp(*motor_ctrl_expt_args.mode->sval, "tri")) {
mc->cfg.expt_mode = MOTOR_CTRL_MODE_TRIANGLE;
printf("expt: mode = triangle\n");
} else if (!strcmp(*motor_ctrl_expt_args.mode->sval, "rect")) {
mc->cfg.expt_mode = MOTOR_CTRL_MODE_RECTANGLE;
printf("expt: mode = rectangle\n");
} else {
mc->cfg.expt_mode = MOTOR_CTRL_MODE_TRIANGLE;
printf("expt: mode = triangle\n");
}
}
xSemaphoreGive(g_motor_mux);
return 0;
}
static int do_motor_ctrl_pid_cmd(int argc, char **argv)
{
int ret = 0;
MOTOR_CTRL_CMD_CHECK(motor_ctrl_pid_args);
xSemaphoreTake(g_motor_mux, portMAX_DELAY);
if (motor_ctrl_pid_args.kp->count) {
mc->pid_param.kp = motor_ctrl_pid_args.kp->dval[0];
printf("pid: kp = %.3f\n", mc->pid_param.kp);
}
if (motor_ctrl_pid_args.ki->count) {
mc->pid_param.ki = motor_ctrl_pid_args.ki->dval[0];
printf("pid: ki = %.3f\n", mc->pid_param.ki);
}
if (motor_ctrl_pid_args.kd->count) {
mc->pid_param.kd = motor_ctrl_pid_args.kd->dval[0];
printf("pid: kd = %.3f\n", mc->pid_param.kd);
}
if (motor_ctrl_pid_args.type->count) {
if (!strcmp(motor_ctrl_pid_args.type->sval[0], "loc")) {
mc->pid_param.cal_type = PID_CAL_TYPE_POSITIONAL;
printf("pid: type = positional\n");
} else if (!strcmp(motor_ctrl_pid_args.type->sval[0], "inc")) {
mc->pid_param.cal_type = PID_CAL_TYPE_INCREMENTAL;
printf("pid: type = incremental\n");
} else {
printf("Invalid pid type:%s\n", motor_ctrl_pid_args.type->sval[0]);
ret = 1;
}
}
pid_update_parameters(mc->pid, &mc->pid_param);
xSemaphoreGive(g_motor_mux);
return ret;
}
static int do_motor_ctrl_motor_cmd(int argc, char **argv)
{
MOTOR_CTRL_CMD_CHECK(motor_ctrl_motor_args);
xSemaphoreTake(g_motor_mux, portMAX_DELAY);
if (motor_ctrl_motor_args.start->count) {
mc->cfg.running_sec = motor_ctrl_motor_args.start->ival[0];
// Start the motor
brushed_motor_start(mc);
mc->cfg.running_sec ?
printf("motor: motor starts to run in %d seconds\n", mc->cfg.running_sec) :
printf("motor: motor starts to run, input 'motor -d' to stop it\n");
}
if (motor_ctrl_motor_args.stop->count) {
// Stop the motor
brushed_motor_stop(mc);
printf("motor: motor stoped\n");
}
xSemaphoreGive(g_motor_mux);
return 0;
}
static void register_motor_ctrl_config(void)
{
motor_ctrl_config_args.pid_flag = arg_str0(NULL, "pid", "<y|n>", "Enable or disable PID algorithm");
motor_ctrl_config_args.period = arg_int0("T", "period", "<ms>", "Set motor control period");
motor_ctrl_config_args.show = arg_lit0("s", "show", "Show current configurations");
motor_ctrl_config_args.end = arg_end(2);
const esp_console_cmd_t motor_ctrl_cfg_cmd = {
.command = "config",
.help = "Enable or disable PID and set motor control period",
.hint = "config -s",
.func = &do_motor_ctrl_config_cmd,
.argtable = &motor_ctrl_config_args
};
ESP_ERROR_CHECK(esp_console_cmd_register(&motor_ctrl_cfg_cmd));
}
static void register_motor_ctrl_expt(void)
{
motor_ctrl_expt_args.init = arg_dbl0("i", "init", "<duty>", "Initial expectation. Usually between -100~100");
motor_ctrl_expt_args.max = arg_dbl0(NULL, "max", "<duty>", "Max limitation for dynamic expectation");
motor_ctrl_expt_args.min = arg_dbl0(NULL, "min", "<duty>", "Min limitation for dynamic expectation");
motor_ctrl_expt_args.pace = arg_dbl0("p", "pace", "<double>", "The increasing pace of expectation every 50ms");
motor_ctrl_expt_args.mode = arg_str0("m", "mode", "<fixed/tri/rect>",
"Select static or dynamic expectation wave mode. 'fixed' for static, 'tri' for triangle, 'rect' for rectangle");
motor_ctrl_expt_args.end = arg_end(2);
const esp_console_cmd_t motor_ctrl_expt_cmd = {
.command = "expt",
.help = "Set initial value, limitation and wave mode of expectation. Both dynamic and static mode are available",
.hint = "expt -i <duty> -m <fixed/tri/rect> -p <double> --max <duty> --min <duty>",
.func = &do_motor_ctrl_expt_cmd,
.argtable = &motor_ctrl_expt_args
};
ESP_ERROR_CHECK(esp_console_cmd_register(&motor_ctrl_expt_cmd));
}
static void register_motor_ctrl_pid(void)
{
motor_ctrl_pid_args.kp = arg_dbl0("p", "kp", "<double>", "Set Kp value for PID");
motor_ctrl_pid_args.ki = arg_dbl0("i", "ki", "<double>", "Set Ki value for PID");
motor_ctrl_pid_args.kd = arg_dbl0("d", "kd", "<double>", "Set Kd value for PID");
motor_ctrl_pid_args.type = arg_str0("t", "type", "<loc/inc>", "Select locational PID or incremental PID");
motor_ctrl_pid_args.end = arg_end(2);
const esp_console_cmd_t motor_ctrl_pid_cmd = {
.command = "pid",
.help = "Set parameters and type for PID algorithm",
.hint = "pid -p <double> -i <double> -d <double> -t <loc/inc>",
.func = &do_motor_ctrl_pid_cmd,
.argtable = &motor_ctrl_pid_args
};
ESP_ERROR_CHECK(esp_console_cmd_register(&motor_ctrl_pid_cmd));
}
static void register_motor_ctrl_motor(void)
{
motor_ctrl_motor_args.start = arg_int0("u", "start", "<seconds>", "Set running seconds for motor, set '0' to keep motor running");
motor_ctrl_motor_args.stop = arg_lit0("d", "stop", "Stop the motor");
motor_ctrl_motor_args.end = arg_end(2);
const esp_console_cmd_t motor_ctrl_motor_cmd = {
.command = "motor",
.help = "Start or stop the motor",
.hint = "motor -u 10",
.func = &do_motor_ctrl_motor_cmd,
.argtable = &motor_ctrl_motor_args
};
ESP_ERROR_CHECK(esp_console_cmd_register(&motor_ctrl_motor_cmd));
}
void cmd_mcpwm_motor_init(mcpwm_motor_control_t *motor_ctrl)
{
mc = motor_ctrl;
esp_console_repl_t *repl = NULL;
esp_console_repl_config_t repl_config = ESP_CONSOLE_REPL_CONFIG_DEFAULT();
repl_config.prompt = "mcpwm-motor>";
// install console REPL environment
#if CONFIG_ESP_CONSOLE_UART
esp_console_dev_uart_config_t uart_config = ESP_CONSOLE_DEV_UART_CONFIG_DEFAULT();
ESP_ERROR_CHECK(esp_console_new_repl_uart(&uart_config, &repl_config, &repl));
#elif CONFIG_ESP_CONSOLE_USB_CDC
esp_console_dev_usb_cdc_config_t cdc_config = ESP_CONSOLE_DEV_CDC_CONFIG_DEFAULT();
ESP_ERROR_CHECK(esp_console_new_repl_usb_cdc(&cdc_config, &repl_config, &repl));
#endif
register_motor_ctrl_config();
register_motor_ctrl_expt();
register_motor_ctrl_pid();
register_motor_ctrl_motor();
printf("\n =================================================================\n");
printf(" | Example of Motor Control |\n");
printf(" | |\n");
printf(" | 1. Try 'help', check all supported commands |\n");
printf(" | 2. Try 'config' to set control period or pwm frequency |\n");
printf(" | 3. Try 'pid' to configure pid paremeters |\n");
printf(" | 4. Try 'expt' to set expectation value and mode |\n");
printf(" | 5. Try 'motor' to start motor in several seconds or stop it |\n");
printf(" | |\n");
printf(" =================================================================\n\n");
printf("Default configuration are shown as follows.\nYou can input 'config -s' to check current status.");
print_current_status();
// start console REPL
ESP_ERROR_CHECK(esp_console_start_repl(repl));
}

View File

@ -1,310 +0,0 @@
/* brushed dc motor control example
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
/*
* This example will show you how to use MCPWM module to control brushed dc motor.
* This code is tested with L298 motor driver.
* User may need to make changes according to the motor driver they use.
*/
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "esp_attr.h"
#include "driver/mcpwm.h"
#include "soc/mcpwm_periph.h"
#include "driver/pcnt.h"
#include "mcpwm_brushed_dc_control_example.h"
#define MOTOR_CTRL_MCPWM_UNIT MCPWM_UNIT_0
#define MOTOR_CTRL_MCPWM_TIMER MCPWM_TIMER_0
/* The global infomation structure */
static mcpwm_motor_control_t motor_ctrl;
SemaphoreHandle_t g_motor_mux;
/**
* @brief Initialize the gpio as mcpwm output
*/
static void mcpwm_example_gpio_initialize(void)
{
printf("initializing mcpwm gpio...\n");
mcpwm_gpio_init(MOTOR_CTRL_MCPWM_UNIT, MCPWM0A, GPIO_PWM0A_OUT);
mcpwm_gpio_init(MOTOR_CTRL_MCPWM_UNIT, MCPWM0B, GPIO_PWM0B_OUT);
}
/**
* @brief set motor moves speed and direction with duty cycle = duty %
*/
void brushed_motor_set_duty(float duty_cycle)
{
/* motor moves in forward direction, with duty cycle = duty % */
if (duty_cycle > 0) {
mcpwm_set_signal_low(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_A);
mcpwm_set_duty(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_B, duty_cycle);
mcpwm_set_duty_type(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_B, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
}
/* motor moves in backward direction, with duty cycle = -duty % */
else {
mcpwm_set_signal_low(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_B);
mcpwm_set_duty(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_A, -duty_cycle);
mcpwm_set_duty_type(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, MCPWM_OPR_A, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state
}
}
/**
* @brief start motor
*
* @param mc mcpwm_motor_control_t pointer
*/
void brushed_motor_start(mcpwm_motor_control_t *mc)
{
motor_ctrl_timer_start();
mc->sec_cnt = 0;
mc->start_flag = true;
}
/**
* @brief stop motor
*
* @param mc mcpwm_motor_control_t pointer
*/
void brushed_motor_stop(mcpwm_motor_control_t *mc)
{
mc->expt = 0;
mc->sec_cnt = 0;
mc->start_flag = false;
motor_ctrl_timer_stop();
brushed_motor_set_duty(0);
}
/**
* @brief The callback function of timer interrupt
* @note This callback is called by timer interrupt callback. It need to offer the PCNT pulse in one control period for PID calculation
* @param args the rotary_encoder_t pointer, it is given by timer interrupt callback
* @return
* - int: the PCNT pulse in one control period
*/
static int pcnt_get_pulse_callback(void *args)
{
/* Record the last count value */
static unsigned int last_pulse = 0;
/* Get the encoder from args */
rotary_encoder_t *encoder = (rotary_encoder_t *)args;
/* Get the value current count value */
unsigned int temp = encoder->get_counter_value(encoder);
/* Calculate the pulse count in one control period */
unsigned int ret = temp - last_pulse;
/* Update last count value */
last_pulse = temp;
return (int)ret;
}
/**
* @brief Initialize the PCNT rotaty encoder
*/
static void motor_ctrl_default_init(void)
{
motor_ctrl.cfg.pid_enable = true;
motor_ctrl.pid_param.kp = 0.8;
motor_ctrl.pid_param.ki = 0.0;
motor_ctrl.pid_param.kd = 0.1;
motor_ctrl.pid_param.cal_type = PID_CAL_TYPE_INCREMENTAL;
motor_ctrl.pid_param.max_output = 100;
motor_ctrl.pid_param.min_output = -100;
motor_ctrl.pid_param.max_integral = 1000;
motor_ctrl.pid_param.min_integral = -1000;
motor_ctrl.cfg.expt_init = 30;
motor_ctrl.cfg.expt_mode = MOTOR_CTRL_MODE_TRIANGLE;
motor_ctrl.cfg.expt_max = 50;
motor_ctrl.cfg.expt_min = -50;
motor_ctrl.cfg.expt_pace = 1.0;
motor_ctrl.cfg.pwm_freq = 1000;
motor_ctrl.cfg.running_sec = 10;
motor_ctrl.cfg.ctrl_period = 10;
}
/**
* @brief Initialize the PCNT rotaty encoder
*/
static void motor_ctrl_pcnt_rotary_encoder_init(void)
{
/* Rotary encoder underlying device is represented by a PCNT unit in this example */
uint32_t pcnt_unit = 0;
/* Create rotary encoder instance */
rotary_encoder_config_t config = ROTARY_ENCODER_DEFAULT_CONFIG(
(rotary_encoder_dev_t)pcnt_unit,
GPIO_PCNT_PINA, GPIO_PCNT_PINB);
ESP_ERROR_CHECK(rotary_encoder_new_ec11(&config, &motor_ctrl.encoder));
/* Filter out glitch (1us) */
ESP_ERROR_CHECK(motor_ctrl.encoder->set_glitch_filter(motor_ctrl.encoder, 1));
/* Start encoder */
ESP_ERROR_CHECK(motor_ctrl.encoder->start(motor_ctrl.encoder));
pcnt_counter_clear((pcnt_unit_t)pcnt_unit);
}
/**
* @brief Initialize the MCPWM
*/
static void motor_ctrl_mcpwm_init(void)
{
/* mcpwm gpio initialization */
mcpwm_example_gpio_initialize();
/* initial mcpwm configuration */
printf("Configuring Initial Parameters of mcpwm...\n");
mcpwm_config_t pwm_config;
pwm_config.frequency = motor_ctrl.cfg.pwm_freq; //frequency = 1kHz,
pwm_config.cmpr_a = 0; //initial duty cycle of PWMxA = 0
pwm_config.cmpr_b = 0; //initial duty cycle of PWMxb = 0
pwm_config.counter_mode = MCPWM_UP_COUNTER; //up counting mode
pwm_config.duty_mode = MCPWM_DUTY_MODE_0;
mcpwm_init(MOTOR_CTRL_MCPWM_UNIT, MOTOR_CTRL_MCPWM_TIMER, &pwm_config); //Configure PWM0A & PWM0B with above settings
}
/**
* @brief Initialize the timer
*/
static void motor_ctrl_timer_init(void)
{
/* Initialize timer alarm event queue */
motor_ctrl.timer_evt_que = xQueueCreate(10, sizeof(motor_ctrl_timer_info_t));
/* Set PCNT rotary encoder handler and pulse getting callback function */
pulse_info_t pulse_info = {.callback_args = motor_ctrl.encoder,
.get_pulse_callback = pcnt_get_pulse_callback
};
motor_ctrl_new_timer(&motor_ctrl.timer_info, motor_ctrl.timer_evt_que, motor_ctrl.cfg.ctrl_period, pulse_info);
}
/**
* @brief the top initialization function in this example
*/
static void motor_ctrl_init_all(void)
{
/* 1. Set default configurations */
motor_ctrl_default_init();
/* 2.rotary encoder initialization */
motor_ctrl_pcnt_rotary_encoder_init();
/* 3.MCPWM initialization */
motor_ctrl_mcpwm_init();
/* 4.pid_ctrl initialization */
pid_ctrl_config_t pid_config = {
.init_param = motor_ctrl.pid_param,
};
pid_new_control_block(&pid_config, &motor_ctrl.pid);
/* 5.Timer initialization */
motor_ctrl_timer_init();
}
/**
* @brief Motor control thread
*
* @param arg Information pointer transmitted by task creating function
*/
static void mcpwm_brushed_motor_ctrl_thread(void *arg)
{
motor_ctrl_timer_info_t recv_info;
while (1) {
/* Wait for recieving information of timer interrupt from timer event queque */
xQueueReceive(motor_ctrl.timer_evt_que, &recv_info, portMAX_DELAY);
/* Get the pcnt pulse during one control period */
motor_ctrl.pulse_in_one_period = recv_info.pulse_info.pulse_cnt;
if (motor_ctrl.cfg.pid_enable) {
/* Calculate the output by PID algorithm according to the pulse. Pid_output here is the duty of MCPWM */
motor_ctrl.error = motor_ctrl.expt - motor_ctrl.pulse_in_one_period;
pid_compute(motor_ctrl.pid, motor_ctrl.error, &motor_ctrl.pid_output);
} else {
motor_ctrl.pid_output = motor_ctrl.expt;
}
/* Set the MCPWM duty */
brushed_motor_set_duty(motor_ctrl.pid_output);
}
}
/**
* @brief Motor control thread
*
* @param arg Information pointer transmitted by task creating function
*/
static void mcpwm_brushed_motor_expt_thread(void *arg)
{
float cnt = 0;
while (1) {
xSemaphoreTake(g_motor_mux, portMAX_DELAY);
switch (motor_ctrl.cfg.expt_mode) {
/* Static expectation */
case MOTOR_CTRL_MODE_FIXED:
motor_ctrl.expt = motor_ctrl.cfg.expt_init;
break;
/* Dynamic expectation: triangle wave */
case MOTOR_CTRL_MODE_TRIANGLE:
motor_ctrl.expt += motor_ctrl.cfg.expt_pace;
motor_ctrl.cfg.expt_pace = (motor_ctrl.expt > motor_ctrl.cfg.expt_max - 0.0001 ||
motor_ctrl.expt < motor_ctrl.cfg.expt_min + 0.0001) ?
- motor_ctrl.cfg.expt_pace : motor_ctrl.cfg.expt_pace;
break;
/* Dynamic expectation: rectangle wave */
case MOTOR_CTRL_MODE_RECTANGLE:
cnt += motor_ctrl.cfg.expt_pace;
if (cnt > motor_ctrl.cfg.expt_max - 0.0001) {
motor_ctrl.cfg.expt_pace = -motor_ctrl.cfg.expt_pace;
motor_ctrl.expt = motor_ctrl.cfg.expt_min;
}
if (cnt < motor_ctrl.cfg.expt_min - 0.0001) {
motor_ctrl.cfg.expt_pace = -motor_ctrl.cfg.expt_pace;
motor_ctrl.expt = motor_ctrl.cfg.expt_max;
}
break;
default:
motor_ctrl.expt = motor_ctrl.cfg.expt_init;
break;
}
xSemaphoreGive(g_motor_mux);
/* Motor automatic stop judgement */
if (motor_ctrl.start_flag) {
motor_ctrl.sec_cnt++;
/* Show the seconds count */
if ((motor_ctrl.sec_cnt + 1) % 20 == 0) {
printf("%d\n", (motor_ctrl.sec_cnt + 1) / 20);
}
/* Stop motor if time up */
if (motor_ctrl.sec_cnt > 20 * motor_ctrl.cfg.running_sec && motor_ctrl.cfg.running_sec != 0) {
brushed_motor_stop(&motor_ctrl);
printf("\nTime up: motor stoped\n");
}
}
/* Delay 50ms */
vTaskDelay(50 / portTICK_PERIOD_MS);
}
}
/**
* @brief The main entry of this example
*/
void app_main(void)
{
printf("Testing brushed motor with PID...\n");
/* Create semaphore */
g_motor_mux = xSemaphoreCreateMutex();
/* Initialize peripherals and modules */
motor_ctrl_init_all();
/* Initialize the console */
cmd_mcpwm_motor_init(&motor_ctrl);
/* Motor control thread */
xTaskCreate(mcpwm_brushed_motor_ctrl_thread, "mcpwm_brushed_motor_ctrl_thread", 4096, NULL, 3, NULL);
/* Motor expectation wave generate thread */
xTaskCreate(mcpwm_brushed_motor_expt_thread, "mcpwm_brushed_motor_expt_thread", 4096, NULL, 5, NULL);
}

View File

@ -1,99 +0,0 @@
/* cmd_mcpwm_motor.h
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#pragma once
#include "rotary_encoder.h"
#include "motor_ctrl_timer.h"
#include "pid_ctrl.h"
#ifdef __cplusplus
extern "C" {
#endif
#define GPIO_PWM0A_OUT 15 //Set GPIO 15 as PWM0A
#define GPIO_PWM0B_OUT 16 //Set GPIO 16 as PWM0B
#define GPIO_PCNT_PINA 18 //Set GPIO 18 as phaseA/C1
#define GPIO_PCNT_PINB 19 //Set GPIO 19 as phaseB/C2
typedef enum {
MOTOR_CTRL_MODE_FIXED = 0,
MOTOR_CTRL_MODE_TRIANGLE,
MOTOR_CTRL_MODE_RECTANGLE
} expect_mode_t;
typedef struct {
/* Handles */
rotary_encoder_t *encoder; // PCNT rotary encoder handler
motor_ctrl_timer_info_t *timer_info; // Timer infomation handler
pid_ctrl_block_handle_t pid; // PID algoritm handler
pid_ctrl_parameter_t pid_param; // PID parameters
QueueHandle_t timer_evt_que; // Timer event queue handler
/* Control visualization */
int pulse_in_one_period; // PCNT pulse in one control period
float error; // The error between the expectation(expt) and actual value (pulse_in_one_period)
float expt; // The expectation
float pid_output; // PID algorithm output
/* Status */
unsigned int sec_cnt; // Seconds count
bool start_flag; // Motor start flag
/* Configurations */
struct {
/* PID configuration */
bool pid_enable; // PID enable flag
/* Expectation configuration */
float expt_init; // Initial expectation
float expt_max; // Max expectation in dynamic mode
float expt_min; // Min expectation in dynamic mode
float expt_pace; // The expection pace. It can change expectation wave period
expect_mode_t expt_mode; // Expectation wave mode (MOTOR_CTRL_EXPT_FIXED/MOTOR_CTRL_EXPT_TRIANGLE/MOTOR_CTRL_EXPT_RECTANGLE)
/* Other configurations */
unsigned int ctrl_period; // Control period
unsigned int pwm_freq; // MCPWM output frequency
unsigned int running_sec; // Motor running seconds
} cfg; // Configurations that should be initialized for this example
} mcpwm_motor_control_t;
/**
* @brief Set pwm duty to drive the motor
*
* @param duty_cycle PWM duty cycle (100~-100), the motor will go backward if the duty is set to a negative value
*/
void brushed_motor_set_duty(float duty_cycle);
/**
* @brief start motor
*
* @param mc mcpwm_motor_control_t pointer
*/
void brushed_motor_start(mcpwm_motor_control_t *mc);
/**
* @brief stop motor
*
* @param mc mcpwm_motor_control_t pointer
*/
void brushed_motor_stop(mcpwm_motor_control_t *mc);
/**
* @brief Initialize the motor control console
*
* @param motor_ctrl The top infomation struct of this example
*/
extern void cmd_mcpwm_motor_init(mcpwm_motor_control_t *motor_ctrl);
#ifdef __cplusplus
}
#endif

View File

@ -14,7 +14,7 @@
#include "freertos/queue.h"
#include "driver/gpio.h"
#include "driver/dac.h"
#include "driver/timer.h"
#include "driver/gptimer.h"
#include "esp_log.h"
/* The timer ISR has an execution time of 5.5 micro-seconds(us).
@ -22,21 +22,14 @@
7 us is a safe interval that will not trigger the watchdog. No need to customize it.
*/
#define WITH_RELOAD 1
#define TIMER_INTR_US 7 // Execution time of each ISR interval in micro-seconds
#define TIMER_DIVIDER 16
#define POINT_ARR_LEN 200 // Length of points array
#define AMP_DAC 255 // Amplitude of DAC voltage. If it's more than 256 will causes dac_output_voltage() output 0.
#define VDD 3300 // VDD is 3.3V, 3300mV
#define CONST_PERIOD_2_PI 6.2832
#define SEC_TO_MICRO_SEC(x) ((x) / 1000 / 1000) // Convert second to micro-second
#define UNUSED_PARAM __attribute__((unused)) // A const period parameter which equals 2 * pai, used to calculate raw dac output value.
#define TIMER_TICKS (TIMER_BASE_CLK / TIMER_DIVIDER) // TIMER_BASE_CLK = APB_CLK = 80MHz
#define ALARM_VAL_US SEC_TO_MICRO_SEC(TIMER_INTR_US * TIMER_TICKS) // Alarm value in micro-seconds
#define OUTPUT_POINT_NUM (int)(1000000 / (TIMER_INTR_US * FREQ) + 0.5) // The number of output wave points.
#define DAC_CHAN CONFIG_EXAMPLE_DAC_CHANNEL // DAC_CHANNEL_1 (GPIO25) by default
#define FREQ CONFIG_EXAMPLE_WAVE_FREQUENCY // 3kHz by default
#define OUTPUT_POINT_NUM (int)(1000000 / (TIMER_INTR_US * FREQ) + 0.5) // The number of output wave points.
_Static_assert(OUTPUT_POINT_NUM <= POINT_ARR_LEN, "The CONFIG_EXAMPLE_WAVE_FREQUENCY is too low and using too long buffer.");
@ -47,60 +40,33 @@ static const char *TAG = "wave_gen";
static int g_index = 0;
/* Timer interrupt service routine */
static void IRAM_ATTR timer0_ISR(void *ptr)
static bool IRAM_ATTR on_timer_alarm_cb(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
{
timer_group_clr_intr_status_in_isr(TIMER_GROUP_0, TIMER_0);
timer_group_enable_alarm_in_isr(TIMER_GROUP_0, TIMER_0);
int *head = (int*)ptr;
int *head = (int *)user_data;
/* DAC output ISR has an execution time of 4.4 us*/
if (g_index >= OUTPUT_POINT_NUM) g_index = 0;
if (g_index >= OUTPUT_POINT_NUM) {
g_index = 0;
}
dac_output_voltage(DAC_CHAN, *(head + g_index));
g_index++;
return false;
}
/* Timer group0 TIMER_0 initialization */
static void example_timer_init(int timer_idx, bool auto_reload)
static void prepare_data(int pnt_num)
{
esp_err_t ret;
timer_config_t config = {
.divider = TIMER_DIVIDER,
.counter_dir = TIMER_COUNT_UP,
.counter_en = TIMER_PAUSE,
.alarm_en = TIMER_ALARM_EN,
.intr_type = TIMER_INTR_LEVEL,
.auto_reload = auto_reload,
};
ret = timer_init(TIMER_GROUP_0, timer_idx, &config);
ESP_ERROR_CHECK(ret);
ret = timer_set_counter_value(TIMER_GROUP_0, timer_idx, 0x00000000ULL);
ESP_ERROR_CHECK(ret);
ret = timer_set_alarm_value(TIMER_GROUP_0, timer_idx, ALARM_VAL_US);
ESP_ERROR_CHECK(ret);
ret = timer_enable_intr(TIMER_GROUP_0, TIMER_0);
ESP_ERROR_CHECK(ret);
/* Register an ISR handler */
timer_isr_register(TIMER_GROUP_0, timer_idx, timer0_ISR, (void *)raw_val, 0, NULL);
}
static void prepare_data(int pnt_num)
{
timer_pause(TIMER_GROUP_0, TIMER_0);
for (int i = 0; i < pnt_num; i ++) {
#ifdef CONFIG_EXAMPLE_WAVEFORM_SINE
raw_val[i] = (int)((sin( i * CONST_PERIOD_2_PI / pnt_num) + 1) * (double)(AMP_DAC)/2 + 0.5);
#elif CONFIG_EXAMPLE_WAVEFORM_TRIANGLE
raw_val[i] = (i > (pnt_num/2)) ? (2 * AMP_DAC * (pnt_num - i) / pnt_num) : (2 * AMP_DAC * i / pnt_num);
#elif CONFIG_EXAMPLE_WAVEFORM_SAWTOOTH
raw_val[i] = (i == pnt_num) ? 0 : (i * AMP_DAC / pnt_num);
#elif CONFIG_EXAMPLE_WAVEFORM_SQUARE
raw_val[i] = (i < (pnt_num/2)) ? AMP_DAC : 0;
#endif
#ifdef CONFIG_EXAMPLE_WAVEFORM_SINE
raw_val[i] = (int)((sin( i * CONST_PERIOD_2_PI / pnt_num) + 1) * (double)(AMP_DAC) / 2 + 0.5);
#elif CONFIG_EXAMPLE_WAVEFORM_TRIANGLE
raw_val[i] = (i > (pnt_num / 2)) ? (2 * AMP_DAC * (pnt_num - i) / pnt_num) : (2 * AMP_DAC * i / pnt_num);
#elif CONFIG_EXAMPLE_WAVEFORM_SAWTOOTH
raw_val[i] = (i == pnt_num) ? 0 : (i * AMP_DAC / pnt_num);
#elif CONFIG_EXAMPLE_WAVEFORM_SQUARE
raw_val[i] = (i < (pnt_num / 2)) ? AMP_DAC : 0;
#endif
volt_val[i] = (int)(VDD * raw_val[i] / (float)AMP_DAC);
}
timer_start(TIMER_GROUP_0, TIMER_0);
}
static void log_info(void)
@ -111,15 +77,15 @@ static void log_info(void)
} else {
ESP_LOGI(TAG, "GPIO:%d", GPIO_NUM_26);
}
#ifdef CONFIG_EXAMPLE_WAVEFORM_SINE
ESP_LOGI(TAG, "Waveform: SINE");
#elif CONFIG_EXAMPLE_WAVEFORM_TRIANGLE
ESP_LOGI(TAG, "Waveform: TRIANGLE");
#elif CONFIG_EXAMPLE_WAVEFORM_SAWTOOTH
ESP_LOGI(TAG, "Waveform: SAWTOOTH");
#elif CONFIG_EXAMPLE_WAVEFORM_SQUARE
ESP_LOGI(TAG, "Waveform: SQUARE");
#endif
#ifdef CONFIG_EXAMPLE_WAVEFORM_SINE
ESP_LOGI(TAG, "Waveform: SINE");
#elif CONFIG_EXAMPLE_WAVEFORM_TRIANGLE
ESP_LOGI(TAG, "Waveform: TRIANGLE");
#elif CONFIG_EXAMPLE_WAVEFORM_SAWTOOTH
ESP_LOGI(TAG, "Waveform: SAWTOOTH");
#elif CONFIG_EXAMPLE_WAVEFORM_SQUARE
ESP_LOGI(TAG, "Waveform: SQUARE");
#endif
ESP_LOGI(TAG, "Frequency(Hz): %d", FREQ);
ESP_LOGI(TAG, "Output points num: %d\n", OUTPUT_POINT_NUM);
@ -127,23 +93,38 @@ static void log_info(void)
void app_main(void)
{
esp_err_t ret;
example_timer_init(TIMER_0, WITH_RELOAD);
ret = dac_output_enable(DAC_CHAN);
ESP_ERROR_CHECK(ret);
g_index = 0;
gptimer_handle_t gptimer = NULL;
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_APB,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = 1000000, // 1MHz, 1 tick = 1us
};
ESP_ERROR_CHECK(gptimer_new_timer(&timer_config, &gptimer));
ESP_ERROR_CHECK(dac_output_enable(DAC_CHAN));
log_info();
g_index = 0;
prepare_data(OUTPUT_POINT_NUM);
while(1) {
gptimer_alarm_config_t alarm_config = {
.reload_count = 0,
.alarm_count = TIMER_INTR_US,
.flags.auto_reload_on_alarm = true,
};
gptimer_event_callbacks_t cbs = {
.on_alarm = on_timer_alarm_cb,
};
ESP_ERROR_CHECK(gptimer_register_event_callbacks(gptimer, &cbs, raw_val));
ESP_ERROR_CHECK(gptimer_set_alarm_action(gptimer, &alarm_config));
ESP_ERROR_CHECK(gptimer_start(gptimer));
while (1) {
vTaskDelay(10);
#if CONFIG_EXAMPLE_LOG_VOLTAGE
if (g_index < OUTPUT_POINT_NUM) {
ESP_LOGI(TAG, "Output voltage(mV): %d", volt_val[g_index]);
ESP_LOGD(TAG, "g_index: %d\n", g_index);
}
#endif
#if CONFIG_EXAMPLE_LOG_VOLTAGE
if (g_index < OUTPUT_POINT_NUM) {
ESP_LOGI(TAG, "Output voltage(mV): %d", volt_val[g_index]);
ESP_LOGD(TAG, "g_index: %d\n", g_index);
}
#endif
}
}

View File

@ -9,22 +9,17 @@
#include <stdio.h>
#include <sys/select.h>
#include "driver/timer.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_err.h"
#include "esp_log.h"
#include "esp_vfs.h"
#include "esp_vfs_dev.h"
#include "esp_vfs_eventfd.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "hal/timer_types.h"
#include "driver/gptimer.h"
#define TIMER_DIVIDER 16
#define TIMER_SCALE (TIMER_BASE_CLK / TIMER_DIVIDER)
#define MS_PER_S 1000
#define TIMER_INTERVAL_SEC 2.5
#define TEST_WITHOUT_RELOAD 0
#define TIMER_RESOLUTION 1000000 // 1MHz, 1 tick = 1us
#define TIMER_INTERVAL_US 2500000 // 2.5s
#define PROGRESS_INTERVAL_MS 3500
#define TIMER_SIGNAL 1
#define PROGRESS_SIGNAL 2
@ -37,22 +32,10 @@ static const char *TAG = "eventfd_example";
static int s_timer_fd;
static int s_progress_fd;
static TaskHandle_t s_worker_handle;
static gptimer_handle_t s_gptimer;
static bool eventfd_timer_isr_callback(void *arg)
static bool eventfd_timer_isr_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_ctx)
{
int timer_idx = (int) arg;
uint32_t timer_intr = timer_group_get_intr_status_in_isr(TIMER_GROUP_0);
uint64_t timer_counter_value = timer_group_get_counter_value_in_isr(TIMER_GROUP_0, timer_idx);
if (timer_intr & TIMER_INTR_T0) {
timer_group_clr_intr_status_in_isr(TIMER_GROUP_0, TIMER_0);
timer_counter_value += (uint64_t) (TIMER_INTERVAL_SEC * TIMER_SCALE);
timer_group_set_alarm_value_in_isr(TIMER_GROUP_0, timer_idx, timer_counter_value);
}
timer_group_enable_alarm_in_isr(TIMER_GROUP_0, timer_idx);
uint64_t signal = TIMER_SIGNAL;
ssize_t val = write(s_timer_fd, &signal, sizeof(signal));
assert(val == sizeof(signal));
@ -60,24 +43,26 @@ static bool eventfd_timer_isr_callback(void *arg)
return true;
}
static void eventfd_timer_init(int timer_idx, double timer_interval_sec)
static void eventfd_timer_init(void)
{
timer_config_t config = {
.divider = TIMER_DIVIDER,
.counter_dir = TIMER_COUNT_UP,
.counter_en = TIMER_PAUSE,
.alarm_en = TIMER_ALARM_EN,
.auto_reload = true,
gptimer_config_t timer_config = {
.clk_src = GPTIMER_CLK_SRC_APB,
.direction = GPTIMER_COUNT_UP,
.resolution_hz = TIMER_RESOLUTION,
};
ESP_ERROR_CHECK(timer_init(TIMER_GROUP_0, timer_idx, &config));
ESP_ERROR_CHECK(gptimer_new_timer(&timer_config, &s_gptimer));
ESP_ERROR_CHECK(timer_set_counter_value(TIMER_GROUP_0, timer_idx, 0x00000000ULL));
ESP_ERROR_CHECK(timer_set_alarm_value(TIMER_GROUP_0, timer_idx, timer_interval_sec * TIMER_SCALE));
ESP_ERROR_CHECK(timer_enable_intr(TIMER_GROUP_0, timer_idx));
ESP_ERROR_CHECK(timer_isr_callback_add(TIMER_GROUP_0, timer_idx, &eventfd_timer_isr_callback, (void*) timer_idx, 0));
ESP_ERROR_CHECK(timer_start(TIMER_GROUP_0, timer_idx));
gptimer_alarm_config_t alarm_config = {
.reload_count = 0,
.alarm_count = TIMER_INTERVAL_US,
.flags.auto_reload_on_alarm = true,
};
gptimer_event_callbacks_t cbs = {
.on_alarm = eventfd_timer_isr_callback,
};
ESP_ERROR_CHECK(gptimer_register_event_callbacks(s_gptimer, &cbs, NULL));
ESP_ERROR_CHECK(gptimer_set_alarm_action(s_gptimer, &alarm_config));
ESP_ERROR_CHECK(gptimer_start(s_gptimer));
}
static void worker_task(void *arg)
@ -163,7 +148,8 @@ static void collector_task(void *arg)
}
}
timer_deinit(TIMER_GROUP_0, TIMER_0);
gptimer_stop(s_gptimer);
gptimer_del_timer(s_gptimer);
close(s_timer_fd);
close(s_progress_fd);
esp_vfs_eventfd_unregister();
@ -172,7 +158,7 @@ static void collector_task(void *arg)
void app_main(void)
{
eventfd_timer_init(TIMER_0, TIMER_INTERVAL_SEC);
eventfd_timer_init();
/* Save the handle for this task as we will need to notify it */
xTaskCreate(worker_task, "worker_task", 4 * 1024, NULL, 5, &s_worker_handle);
xTaskCreate(collector_task, "collector_task", 4 * 1024, NULL, 5, NULL);

View File

@ -2582,8 +2582,6 @@ examples/peripherals/lcd/tjpgd/main/pretty_effect.h
examples/peripherals/ledc/ledc_basic/main/ledc_basic_example_main.c
examples/peripherals/ledc/ledc_fade/main/ledc_fade_example_main.c
examples/peripherals/mcpwm/mcpwm_bldc_hall_control/main/mcpwm_bldc_hall_control_example_main.c
examples/peripherals/mcpwm/mcpwm_brushed_dc_control/components/motor_ctrl_timer/motor_ctrl_timer.c
examples/peripherals/mcpwm/mcpwm_brushed_dc_control/components/motor_ctrl_timer/motor_ctrl_timer.h
examples/peripherals/mcpwm/mcpwm_brushed_dc_control/main/cmd_mcpwm_motor.c
examples/peripherals/mcpwm/mcpwm_brushed_dc_control/main/mcpwm_brushed_dc_control_example.c
examples/peripherals/mcpwm/mcpwm_brushed_dc_control/main/mcpwm_brushed_dc_control_example.h