Skip to content

Instantly share code, notes, and snippets.

@Andrei-Pozolotin
Last active December 13, 2023 01:23
Show Gist options
  • Star 3 You must be signed in to star a gist
  • Fork 1 You must be signed in to fork a gist
  • Save Andrei-Pozolotin/c4b3dd041efe53cfb92cfb4de9c67267 to your computer and use it in GitHub Desktop.
Save Andrei-Pozolotin/c4b3dd041efe53cfb92cfb4de9c67267 to your computer and use it in GitHub Desktop.
esp32.RMT

RE: micropython/micropython#7015

GIST: https://gist.github.com/Andrei-Pozolotin/c4b3dd041efe53cfb92cfb4de9c67267

Here is a working experimental implementation. Basic approach is:

  • use piecewise interpolation for stepper motor pulse profile
  • persist interpolation segments once, inside esp32.RMT.items store
  • start sending pulses from items store with rmt.h | rmt_set_clk_div() and rmt.h | rmt_write_items()
  • continue sending by switching between pulse patterns with rmt.h | rmt_register_tx_end_callback() system ISR

this is accomplished with addition of 2 functions to (a copy with changes:) ports/esp32/esp32_rmt.c

// RMT.store_pulses(self, item_list:list[int]) -> None
STATIC mp_obj_t esp32_rmt_store_pulses(size_t n_args, const mp_obj_t *args) {
    esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0]);
    mp_obj_t item_list_obj = args[1];

    size_t num_items = 0;
    mp_obj_t *item_list_ptr = NULL;
    mp_obj_get_array(item_list_obj, &num_items, &item_list_ptr);

    if (num_items > self->num_items) {
        self->items = (rmt_item32_t *)m_realloc(self->items, num_items * sizeof(rmt_item32_t *));
        self->num_items = num_items;
    }
    
    for (mp_uint_t item_index = 0; item_index < num_items; item_index++) {
        self->items[item_index].val = mp_obj_get_int(item_list_ptr[item_index]);
    }
    
    return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_store_pulses_obj, 2, 2, esp32_rmt_store_pulses);
// RMT.issue_pulses(self, tx_ready_func:callable, item_index:int, item_count:int, clock_div:int) -> None
STATIC mp_obj_t esp32_rmt_issue_pulses(size_t n_args, const mp_obj_t *args) {
    esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0]);
    mp_obj_t *tx_ready_fn = MP_OBJ_TO_PTR(args[1]);
    mp_uint_t item_index = mp_obj_get_int(args[2]);
    mp_uint_t item_count = mp_obj_get_int(args[3]);
    self->clock_div = mp_obj_get_int(args[4]);

    check_esp_err(rmt_set_clk_div(self->channel_id, self->clock_div));
    
    rmt_register_tx_end_callback(esp32_rmt_private_tx_end_callback, tx_ready_fn);
    
    check_esp_err(rmt_write_items(self->channel_id, self->items + item_index, item_count, false));
    
    return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_issue_pulses_obj, 5, 5, esp32_rmt_issue_pulses);

and the following micropython user code:

  • class Planner servo-like motion planner for nema-based stepper driver
  • class Ringer isr-safe ring buffer to store stepper micro-commands
  • class Stepper servo-like nema-based stepper driver based on esp32.RMT driver

with core functionality expressed in: Stepper.make_rotation_one()

    def make_rotation_one(self) -> None:
        "accelerate then decelerate during single drive turn"
        plan_one = self.planner.make_plan_rotate(+1, 0.5)
        plan_two = self.planner.make_plan_rotate(-1, 0.5)
        plan_full = plan_one + plan_two + [PLAN_CMD_STOP]
        # print(f"{plan_full=}")
        self.persist_motion_plan(plan_full)
        self.transmit_reactor()  # start transmit with isr self call

and Stepper.transmit_reactor()

    def transmit_reactor(self):
        """
        function to execute stepper micro-program:
        * invoked by self "make rotation" methods for motion start
        * invoked by esp32.RMT driver "transmit ready" ISR to continue motion
        note: use isr rules https://docs.micropython.org/en/latest/reference/isr_rules.html
        """
        buffer = self.ringer
        header = buffer.ring_get()  # micro-command prefix

        if header == PLAN_CMD_RAMP:
            # micro-command parameters
            item_index = buffer.ring_get()
            item_count = buffer.ring_get()
            clock_div = buffer.ring_get()
            # start pulse sequence form rmt driver store
            self.rmt_driver.issue_pulses(# non blocking invocation
                self.transmit_function,  # this is isr setup to self
                item_index,  # place in the store
                item_count,  # pulse ramp block size
                clock_div,  # frequency for this block
            )
            self.event_cmd_ramp.set()
            return

        if header == PLAN_CMD_STOP:
            self.event_cmd_stop.set()
            return

        self.event_cmd_trap.set()  # should not happen
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 "Matt Trentini" <matt.trentini@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "py/runtime.h"
#include "modmachine.h"
#include "mphalport.h"
#include "modesp32.h"
#include "esp_task.h"
#include "driver/rmt.h"
// This exposes the ESP32's RMT module to MicroPython. RMT is provided by the Espressif ESP-IDF:
//
// https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/rmt.html
//
// With some examples provided:
//
// https://github.com/espressif/arduino-esp32/tree/master/libraries/ESP32/examples/RMT
//
// RMT allows accurate (down to 12.5ns resolution) transmit - and receive - of pulse signals.
// Originally designed to generate infrared remote control signals, the module is very
// flexible and quite easy-to-use.
//
// This current MicroPython implementation lacks some major features, notably receive pulses
// and carrier output.
// Last available RMT channel that can transmit.
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(4, 4, 0)
#define RMT_LAST_TX_CHANNEL (RMT_CHANNEL_MAX - 1)
#else
#define RMT_LAST_TX_CHANNEL (SOC_RMT_TX_CANDIDATES_PER_GROUP - 1)
#endif
// Forward declaration
extern const mp_obj_type_t esp32_rmt_type;
typedef struct _esp32_rmt_obj_t {
mp_obj_base_t base;
uint8_t channel_id;
gpio_num_t pin;
uint8_t clock_div;
mp_uint_t num_items;
rmt_item32_t *items;
bool loop_en;
} esp32_rmt_obj_t;
// Current channel used for machine.bitstream, in the machine_bitstream_high_low_rmt
// implementation. A value of -1 means do not use RMT.
int8_t esp32_rmt_bitstream_channel_id = RMT_LAST_TX_CHANNEL;
#if MP_TASK_COREID == 0
typedef struct _rmt_install_state_t {
SemaphoreHandle_t handle;
uint8_t channel_id;
esp_err_t ret;
} rmt_install_state_t;
STATIC void rmt_install_task(void *pvParameter) {
rmt_install_state_t *state = pvParameter;
state->ret = rmt_driver_install(state->channel_id, 0, 0);
xSemaphoreGive(state->handle);
vTaskDelete(NULL);
for (;;) {
}
}
// Call rmt_driver_install on core 1. This ensures that the RMT interrupt handler is
// serviced on core 1, so that WiFi (if active) does not interrupt it and cause glitches.
esp_err_t rmt_driver_install_core1(uint8_t channel_id) {
TaskHandle_t th;
rmt_install_state_t state;
state.handle = xSemaphoreCreateBinary();
state.channel_id = channel_id;
xTaskCreatePinnedToCore(rmt_install_task, "rmt_install_task", 2048 / sizeof(StackType_t), &state, ESP_TASK_PRIO_MIN + 1, &th, 1);
xSemaphoreTake(state.handle, portMAX_DELAY);
vSemaphoreDelete(state.handle);
return state.ret;
}
#else
// MicroPython runs on core 1, so we can call the RMT installer directly and its
// interrupt handler will also run on core 1.
esp_err_t rmt_driver_install_core1(uint8_t channel_id) {
return rmt_driver_install(channel_id, 0, 0);
}
#endif
STATIC mp_obj_t esp32_rmt_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *all_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_id, MP_ARG_REQUIRED | MP_ARG_INT, {.u_int = -1} },
{ MP_QSTR_pin, MP_ARG_REQUIRED | MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_clock_div, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 8} }, // 100ns resolution
{ MP_QSTR_idle_level, MP_ARG_KW_ONLY | MP_ARG_BOOL, {.u_bool = false} }, // low voltage
{ MP_QSTR_tx_carrier, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} }, // no carrier
};
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all_kw_array(n_args, n_kw, all_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
mp_uint_t channel_id = args[0].u_int;
gpio_num_t pin_id = machine_pin_get_id(args[1].u_obj);
mp_uint_t clock_div = args[2].u_int;
mp_uint_t idle_level = args[3].u_bool;
mp_obj_t tx_carrier_obj = args[4].u_obj;
if (esp32_rmt_bitstream_channel_id >= 0 && channel_id == esp32_rmt_bitstream_channel_id) {
mp_raise_ValueError(MP_ERROR_TEXT("channel used by bitstream"));
}
if (clock_div < 1 || clock_div > 255) {
mp_raise_ValueError(MP_ERROR_TEXT("clock_div must be between 1 and 255"));
}
esp32_rmt_obj_t *self = m_new_obj_with_finaliser(esp32_rmt_obj_t);
self->base.type = &esp32_rmt_type;
self->channel_id = channel_id;
self->pin = pin_id;
self->clock_div = clock_div;
self->loop_en = false;
rmt_config_t config = {0};
config.rmt_mode = RMT_MODE_TX;
config.channel = (rmt_channel_t)self->channel_id;
config.gpio_num = self->pin;
config.mem_block_num = 1;
config.tx_config.loop_en = 0;
if (tx_carrier_obj != mp_const_none) {
mp_obj_t *tx_carrier_details = NULL;
mp_obj_get_array_fixed_n(tx_carrier_obj, 3, &tx_carrier_details);
mp_uint_t frequency = mp_obj_get_int(tx_carrier_details[0]);
mp_uint_t duty = mp_obj_get_int(tx_carrier_details[1]);
mp_uint_t level = mp_obj_is_true(tx_carrier_details[2]);
if (frequency == 0) {
mp_raise_ValueError(MP_ERROR_TEXT("tx_carrier frequency must be >0"));
}
if (duty > 100) {
mp_raise_ValueError(MP_ERROR_TEXT("tx_carrier duty must be 0..100"));
}
config.tx_config.carrier_en = 1;
config.tx_config.carrier_freq_hz = frequency;
config.tx_config.carrier_duty_percent = duty;
config.tx_config.carrier_level = level;
} else {
config.tx_config.carrier_en = 0;
}
config.tx_config.idle_output_en = 1;
config.tx_config.idle_level = idle_level;
config.clk_div = self->clock_div;
check_esp_err(rmt_config(&config));
check_esp_err(rmt_driver_install_core1(config.channel));
return MP_OBJ_FROM_PTR(self);
}
STATIC void esp32_rmt_print(const mp_print_t *print, mp_obj_t self_in, mp_print_kind_t kind) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(self_in);
if (self->pin != -1) {
bool idle_output_en;
rmt_idle_level_t idle_level;
check_esp_err(rmt_get_idle_level(self->channel_id, &idle_output_en, &idle_level));
mp_printf(print, "RMT(channel=%u, pin=%u, source_freq=%u, clock_div=%u, idle_level=%u)",
self->channel_id, self->pin, APB_CLK_FREQ, self->clock_div, idle_level);
} else {
mp_printf(print, "RMT()");
}
}
STATIC mp_obj_t esp32_rmt_deinit(mp_obj_t self_in) {
// fixme: check for valid channel. Return exception if error occurs.
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(self_in);
if (self->pin != -1) { // Check if channel has already been deinitialised.
rmt_driver_uninstall(self->channel_id);
self->pin = -1; // -1 to indicate RMT is unused
m_free(self->items);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp32_rmt_deinit_obj, esp32_rmt_deinit);
// Return the source frequency.
// Currently only the APB clock (80MHz) can be used but it is possible other
// clock sources will added in the future.
STATIC mp_obj_t esp32_rmt_source_freq(mp_obj_t self_in) {
return mp_obj_new_int(APB_CLK_FREQ);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp32_rmt_source_freq_obj, esp32_rmt_source_freq);
// Return the clock divider.
STATIC mp_obj_t esp32_rmt_clock_div(mp_obj_t self_in) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(self_in);
return mp_obj_new_int(self->clock_div);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(esp32_rmt_clock_div_obj, esp32_rmt_clock_div);
// Query whether the channel has finished sending pulses. Takes an optional
// timeout (in milliseconds), returning true if the pulse stream has
// completed or false if they are still transmitting (or timeout is reached).
STATIC mp_obj_t esp32_rmt_wait_done(size_t n_args, const mp_obj_t *pos_args, mp_map_t *kw_args) {
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_self, MP_ARG_REQUIRED | MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_timeout, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 0} },
};
mp_arg_val_t args[MP_ARRAY_SIZE(allowed_args)];
mp_arg_parse_all(n_args, pos_args, kw_args, MP_ARRAY_SIZE(allowed_args), allowed_args, args);
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0].u_obj);
esp_err_t err = rmt_wait_tx_done(self->channel_id, args[1].u_int / portTICK_PERIOD_MS);
return err == ESP_OK ? mp_const_true : mp_const_false;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_KW(esp32_rmt_wait_done_obj, 1, esp32_rmt_wait_done);
STATIC mp_obj_t esp32_rmt_loop(mp_obj_t self_in, mp_obj_t loop) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(self_in);
self->loop_en = mp_obj_get_int(loop);
if (!self->loop_en) {
bool loop_en;
check_esp_err(rmt_get_tx_loop_mode(self->channel_id, &loop_en));
if (loop_en) {
check_esp_err(rmt_set_tx_loop_mode(self->channel_id, false));
check_esp_err(rmt_set_tx_intr_en(self->channel_id, true));
}
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_2(esp32_rmt_loop_obj, esp32_rmt_loop);
STATIC mp_obj_t esp32_rmt_write_pulses(size_t n_args, const mp_obj_t *args) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0]);
mp_obj_t duration_obj = args[1];
mp_obj_t data_obj = n_args > 2 ? args[2] : mp_const_true;
mp_uint_t duration = 0;
size_t duration_length = 0;
mp_obj_t *duration_ptr = NULL;
mp_uint_t data = 0;
size_t data_length = 0;
mp_obj_t *data_ptr = NULL;
mp_uint_t num_pulses = 0;
if (!(mp_obj_is_type(data_obj, &mp_type_tuple) || mp_obj_is_type(data_obj, &mp_type_list))) {
// Mode 1: array of durations, toggle initial data value
mp_obj_get_array(duration_obj, &duration_length, &duration_ptr);
data = mp_obj_is_true(data_obj);
num_pulses = duration_length;
} else if (mp_obj_is_int(duration_obj)) {
// Mode 2: constant duration, array of data values
duration = mp_obj_get_int(duration_obj);
mp_obj_get_array(data_obj, &data_length, &data_ptr);
num_pulses = data_length;
} else {
// Mode 3: arrays of durations and data values
mp_obj_get_array(duration_obj, &duration_length, &duration_ptr);
mp_obj_get_array(data_obj, &data_length, &data_ptr);
if (duration_length != data_length) {
mp_raise_ValueError(MP_ERROR_TEXT("duration and data must have same length"));
}
num_pulses = duration_length;
}
if (num_pulses == 0) {
mp_raise_ValueError(MP_ERROR_TEXT("No pulses"));
}
if (self->loop_en && num_pulses > 126) {
mp_raise_ValueError(MP_ERROR_TEXT("Too many pulses for loop"));
}
mp_uint_t num_items = (num_pulses / 2) + (num_pulses % 2);
if (num_items > self->num_items) {
self->items = (rmt_item32_t *)m_realloc(self->items, num_items * sizeof(rmt_item32_t *));
self->num_items = num_items;
}
for (mp_uint_t item_index = 0, pulse_index = 0; item_index < num_items; item_index++) {
self->items[item_index].duration0 = duration_length ? mp_obj_get_int(duration_ptr[pulse_index]) : duration;
self->items[item_index].level0 = data_length ? mp_obj_is_true(data_ptr[pulse_index]) : data++;
pulse_index++;
if (pulse_index < num_pulses) {
self->items[item_index].duration1 = duration_length ? mp_obj_get_int(duration_ptr[pulse_index]) : duration;
self->items[item_index].level1 = data_length ? mp_obj_is_true(data_ptr[pulse_index]) : data++;
pulse_index++;
} else {
self->items[item_index].duration1 = 0;
self->items[item_index].level1 = 0;
}
}
if (self->loop_en) {
bool loop_en;
check_esp_err(rmt_get_tx_loop_mode(self->channel_id, &loop_en));
if (loop_en) {
check_esp_err(rmt_set_tx_intr_en(self->channel_id, true));
check_esp_err(rmt_set_tx_loop_mode(self->channel_id, false));
}
check_esp_err(rmt_wait_tx_done(self->channel_id, portMAX_DELAY));
}
check_esp_err(rmt_write_items(self->channel_id, self->items, num_items, false));
if (self->loop_en) {
check_esp_err(rmt_set_tx_intr_en(self->channel_id, false));
check_esp_err(rmt_set_tx_loop_mode(self->channel_id, true));
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_write_pulses_obj, 2, 3, esp32_rmt_write_pulses);
// USER
// RMT.store_pulses(self, item_list:list[int32]) -> None
STATIC mp_obj_t esp32_rmt_store_pulses(size_t n_args, const mp_obj_t *args) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0]);
mp_obj_t item_list_obj = args[1];
size_t num_items = 0;
mp_obj_t *item_list_ptr = NULL;
mp_obj_get_array(item_list_obj, &num_items, &item_list_ptr);
if (num_items > self->num_items) {
self->items = (rmt_item32_t *)m_realloc(self->items, num_items * sizeof(rmt_item32_t *));
self->num_items = num_items;
}
for (mp_uint_t item_index = 0; item_index < num_items; item_index++) {
self->items[item_index].val = mp_obj_get_int(item_list_ptr[item_index]);
}
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_store_pulses_obj, 2, 2, esp32_rmt_store_pulses);
#include "py/gc.h"
#include "py/mpthread.h"
#include "py/stackctrl.h"
// called from esp32 RMT system ISR provided by rmt_driver_install()
STATIC void esp32_rmt_private_tx_end_callback(rmt_channel_t channel, void *arg) {
void *state_past = mp_thread_get_state();
mp_state_thread_t state_next;
mp_thread_set_state(&state_next);
mp_stack_set_top(&state_next + 1);
mp_stack_set_limit(1024);
mp_locals_set(mp_state_ctx.thread.dict_locals);
mp_globals_set(mp_state_ctx.thread.dict_globals);
mp_sched_lock();
gc_lock();
mp_obj_t *tx_ready_fn = (mp_obj_t *) arg;
mp_call_function_0(tx_ready_fn);
gc_unlock();
mp_sched_unlock();
mp_thread_set_state(state_past);
}
// RMT.issue_pulses(self, tx_ready_func:callable, item_index:int, item_count:int, clock_div:int) -> None
STATIC mp_obj_t esp32_rmt_issue_pulses(size_t n_args, const mp_obj_t *args) {
esp32_rmt_obj_t *self = MP_OBJ_TO_PTR(args[0]);
mp_obj_t *tx_ready_fn = MP_OBJ_TO_PTR(args[1]);
mp_uint_t item_index = mp_obj_get_int(args[2]);
mp_uint_t item_count = mp_obj_get_int(args[3]);
self->clock_div = mp_obj_get_int(args[4]);
check_esp_err(rmt_set_clk_div(self->channel_id, self->clock_div));
rmt_register_tx_end_callback(esp32_rmt_private_tx_end_callback, tx_ready_fn);
check_esp_err(rmt_write_items(self->channel_id, self->items + item_index, item_count, false));
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_issue_pulses_obj, 5, 5, esp32_rmt_issue_pulses);
// USER
STATIC mp_obj_t esp32_rmt_bitstream_channel(size_t n_args, const mp_obj_t *args) {
if (n_args > 0) {
if (args[0] == mp_const_none) {
esp32_rmt_bitstream_channel_id = -1;
} else {
mp_int_t channel_id = mp_obj_get_int(args[0]);
if (channel_id < 0 || channel_id > RMT_LAST_TX_CHANNEL) {
mp_raise_ValueError(MP_ERROR_TEXT("invalid channel"));
}
esp32_rmt_bitstream_channel_id = channel_id;
}
}
if (esp32_rmt_bitstream_channel_id < 0) {
return mp_const_none;
} else {
return MP_OBJ_NEW_SMALL_INT(esp32_rmt_bitstream_channel_id);
}
}
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR_BETWEEN(esp32_rmt_bitstream_channel_fun_obj, 0, 1, esp32_rmt_bitstream_channel);
STATIC MP_DEFINE_CONST_STATICMETHOD_OBJ(esp32_rmt_bitstream_channel_obj, MP_ROM_PTR(&esp32_rmt_bitstream_channel_fun_obj));
STATIC const mp_rom_map_elem_t esp32_rmt_locals_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR___del__), MP_ROM_PTR(&esp32_rmt_deinit_obj) },
{ MP_ROM_QSTR(MP_QSTR_deinit), MP_ROM_PTR(&esp32_rmt_deinit_obj) },
{ MP_ROM_QSTR(MP_QSTR_source_freq), MP_ROM_PTR(&esp32_rmt_source_freq_obj) },
{ MP_ROM_QSTR(MP_QSTR_clock_div), MP_ROM_PTR(&esp32_rmt_clock_div_obj) },
{ MP_ROM_QSTR(MP_QSTR_wait_done), MP_ROM_PTR(&esp32_rmt_wait_done_obj) },
{ MP_ROM_QSTR(MP_QSTR_loop), MP_ROM_PTR(&esp32_rmt_loop_obj) },
{ MP_ROM_QSTR(MP_QSTR_write_pulses), MP_ROM_PTR(&esp32_rmt_write_pulses_obj) },
// USER
{ MP_ROM_QSTR(MP_QSTR_store_pulses), MP_ROM_PTR(&esp32_rmt_store_pulses_obj) },
{ MP_ROM_QSTR(MP_QSTR_issue_pulses), MP_ROM_PTR(&esp32_rmt_issue_pulses_obj) },
// USER
// Static methods
{ MP_ROM_QSTR(MP_QSTR_bitstream_channel), MP_ROM_PTR(&esp32_rmt_bitstream_channel_obj) },
};
STATIC MP_DEFINE_CONST_DICT(esp32_rmt_locals_dict, esp32_rmt_locals_dict_table);
const mp_obj_type_t esp32_rmt_type = {
{ &mp_type_type },
.name = MP_QSTR_RMT,
.print = esp32_rmt_print,
.make_new = esp32_rmt_make_new,
.locals_dict = (mp_obj_dict_t *)&esp32_rmt_locals_dict,
};
"""
servo-like motion planner for nema-based stepper driver
"""
import micropython
# stepper driver mciro-command headers
PLAN_CMD_RAMP = micropython.const(577) # send ramp pulses
PLAN_CMD_STOP = micropython.const(701) # terminate program
#
# note: rmt_item32_t format (esp32 is little endian)
# https://github.com/espressif/esp-idf/blob/master/components/driver/include/driver/rmt.h
# https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/peripherals/rmt.html
#
# typedef struct {
# union {
# struct {
# uint32_t duration0 : 15; /*!< Duration of level0 */
# uint32_t level0 : 1; /*!< Level of the first part */
# uint32_t duration1 : 15; /*!< Duration of level1 */
# uint32_t level1 : 1; /*!< Level of the second part */
# };
# uint32_t val; /*!< Equivelent unsigned value for the RMT item */
# };
# } rmt_item32_t;
# define single stepper driver pulse as rmt_item32_t entry
# pulse_head -> "rmt first part duration", pulse_tail -> "rmt second part duration"
@micropython.viper # @UndefinedVariable
def make_rmt_item32(pulse_head:int, pulse_tail:int) -> int:
level_head = 1
level_tail = 0
return ((level_head << 15 | pulse_head) << 0) | ((level_tail << 15 | pulse_tail) << 16)
# convert stepper pulses into rmt items
def make_rmt_item_list(head_size:int, period_list:list[int]) -> list["rmt_item32"]:
item_list = []
for period in period_list:
pulse_head = head_size
pulse_tail = period - head_size
rmt_item32 = make_rmt_item32(pulse_head, pulse_tail)
item_list.append(rmt_item32)
return item_list
class Planner:
"""
servo-like motion planner for nema-based stepper driver
"""
def __init__(self,
motor_steps:int=200, # motor steps per turn, count
motor_gear:int=22, # motion source or motor teeth, count
drive_gear:int=85, # motion target or drive teeth, count
drive_freq_zero:float=0.4, # "zero" mode, or drive start up speed, Hz
drive_freq_slow:float=2.0, # "slow" mode drive steady rotation speed, Hz
drive_freq_fast:float=10.0, # "fast" mode drive steady rotation speed, Hz
pulse_size_min:int=40, # stepper driver pulse limit, micro sec
turn_block_count:int=8, # number of ramp blocks in one drive turn, count of block
clock_rate:int=80, # esp32.RMT driver base clock, MHz
clock_div_min:int=10, # rmt clock divider range limit, count
clock_div_max:int=250, # rmt clock divider range limit, count
):
self.motor_steps = motor_steps # motor steps per one motor turn
self.drive_steps = motor_steps * drive_gear / motor_gear # motor steps per one drive turn
self.drive_freq_zero = drive_freq_zero
self.drive_freq_slow = drive_freq_slow
self.drive_freq_fast = drive_freq_fast
self.clock_div_min = clock_div_min
self.clock_div_max = clock_div_max
self.pulse_size_min = pulse_size_min
self.turn_block_count = turn_block_count
self.ramp_block_size_raw = self.drive_steps / turn_block_count
self.ramp_block_size_int = round(self.ramp_block_size_raw) # number of pulses in a ramp, count of item
self.clock_rate = clock_rate
clock_time_min = clock_div_min / self.clock_rate # minimal planner time unit, micro sec
clock_time_max = clock_div_max / self.clock_rate # maximal planner time unit, micro sec
# print(f"{clock_time_min=} {clock_time_max=}")
assert drive_freq_fast < 20 # mechanical limits
assert drive_freq_zero > 0.1 # mechanical limits
assert drive_freq_fast > drive_freq_slow
assert drive_freq_slow > drive_freq_zero
period_base = 1e6 / self.drive_steps
period_zero = period_base / drive_freq_zero # micro sec
period_slow = period_base / drive_freq_slow # micro sec
self.turn_unit_ratio = period_slow / period_zero # speed ratio for single drive turn
self.ramp_unit_ratio = self.turn_unit_ratio ** (1 / turn_block_count) # for single ramp block
# print(f"{self.turn_unit_ratio=:.4f} {self.ramp_unit_ratio=:.4f}")
self.ramp_unit_max = period_zero / clock_time_max # maximum number of rmt items in one pulse
self.ramp_unit_min = self.ramp_unit_max * self.ramp_unit_ratio # minimum number of rmt items in one pulse
# print(f"{self.ramp_unit_max=:.2f} {self.ramp_unit_min=:.2f}")
self.ramp_unit_delta = (self.ramp_unit_max - self.ramp_unit_min) / self.ramp_block_size_int # rmt item change rate
# print(f"{self.ramp_block_size_int=:.2f} {self.ramp_unit_delta=:.2f}")
# rmt item list offsets for the item ramps
self.index_increase = self.ramp_block_size_int * 0
self.index_constant = self.ramp_block_size_int * 1
self.index_decrease = self.ramp_block_size_int * 2
self.item_list_size = self.ramp_block_size_int * 3 # using only 3 ramps
self.this_step_count_int = 0 # remember discrete drive step count
self.this_step_count_raw = 0.0 # remember exact drive step count
self.this_drive_freq = drive_freq_zero # remember current drive rotation speed, Hz
@property
def current_drive_freq(self) -> float:
return self.this_drive_freq
@property
def current_stepper_error(self) -> float:
return self.this_step_count_int - self.this_step_count_raw
def make_item_list(self) -> list["rmt_item32"]:
"""
generate rmt item list stored inside rmt driver esp32.RMT
"""
period_list = self.make_period_list()
head_size = round(self.ramp_unit_min / 2) # split pulse into "head" and "tail" in the middle
item_list = make_rmt_item_list(head_size, period_list) # generate rmt item list
assert len(item_list) == self.item_list_size # ensure total rapms collection
return item_list
def make_period_list(self) -> list[int]:
"""
generate stepper pulse list stitched from pulse blocks: increase, constant, decrease
"""
ramp_decrease = [ # generate speed "decrease"
round(self.ramp_unit_min + index * self.ramp_unit_delta)
for index in range(self.ramp_block_size_int)
]
ramp_increase = [ # generate speed "increase"
round(self.ramp_unit_max - index * self.ramp_unit_delta - self.ramp_unit_delta)
for index in range(self.ramp_block_size_int)
]
ramp_constant = self.ramp_block_size_int * [round(self.ramp_unit_min)] # generate speed "coasting" sequence
# print(f"ramp_decrease head:{ramp_decrease[:+10]} tail:{ramp_decrease[-10:]}")
# print(f"ramp_increase head:{ramp_increase[:+10]} tail:{ramp_increase[-10:]}")
# print(f"ramp_constant head:{ramp_constant[:+10]} tail:{ramp_constant[-10:]}")
assert ramp_increase[-1] == ramp_constant[+0] # ensure ramp stitch level
assert ramp_constant[+0] == ramp_constant[-1] # ensure ramp stitch level
assert ramp_constant[-1] == ramp_decrease[+0] # ensure ramp stitch level
period_list = ramp_increase + ramp_constant + ramp_decrease # keep ramps in order
assert len(period_list) == self.item_list_size # ensure total rapms collection
assert all(
period > self.pulse_size_min # stepper drive pulse limit
and period < 32768 # rmt item duration is in 15-bit range
for period in period_list
)
return period_list
def make_plan_rotate(self,
freq_mode:int, # speed change mode: -1, 0, +1
drive_turn:float, # number of drive turns
) -> list[int]:
"""
generate stepper motion micro-program, executed by stepper driver
"""
# print(f"{self.this_drive_freq=:.2f}")
freq_past = self.this_drive_freq # drive frequency at the beginning of this motion
freq_zero = self.drive_freq_zero # TODO ensure limits
freq_slow = self.drive_freq_slow # TODO ensure limits
freq_fast = self.drive_freq_fast # TODO ensure limits
if freq_mode == 0: # continue
freq_ratio = 1
index_base = self.index_constant
unit_base = self.ramp_unit_min
elif freq_mode < 0: # decelerate
freq_ratio = 1 * self.ramp_unit_ratio
index_base = self.index_decrease
unit_base = self.ramp_unit_min
elif freq_mode > 0: # accelerate
freq_ratio = 1 / self.ramp_unit_ratio
index_base = self.index_increase
unit_base = self.ramp_unit_max
else:
assert False
plan_rotate = [] # stepper command list
clock_rate = self.clock_rate
drive_steps = self.drive_steps
period_base = 1e6 / drive_steps
block_size_int = self.ramp_block_size_int
block_size_raw = self.ramp_block_size_raw
ramp_count = round(drive_turn * self.turn_block_count)
for ramp_index in range(ramp_count):
# correct for discretization error
self.this_step_count_int += block_size_int
self.this_step_count_raw += block_size_raw
block_step_error = round(self.current_stepper_error)
self.this_step_count_int -= block_step_error
# produce ramp motion parameters
freq_next = freq_past * (freq_ratio ** ramp_index)
period_next = period_base / freq_next
clock_time = period_next / unit_base
clock_div = round(clock_rate * clock_time)
# generate motion micro-instruction
item_start = index_base
item_count = block_size_int - block_step_error
plan_block = [PLAN_CMD_RAMP, item_start, item_count, clock_div] # single stepper command
plan_rotate += plan_block
# print(f"{freq_next=:.2f} {clock_time=:.2f} {clock_div=}")
self.this_drive_freq = freq_past * (freq_ratio ** ramp_count) # drive frequency at the end of this motion
# print(f"{self.this_drive_freq=:.2f}")
return plan_rotate
"""
isr-safe ring buffer
"""
import array
import micropython
class Ringer:
"""
note: use isr rules https://docs.micropython.org/en/latest/reference/isr_rules.html
"""
def __init__(self,
ring_power:int=6, # base 2 log of ring size
ring_type:object="H", # unsigned short
):
self.ring_power:int = ring_power
self.ring_size:int = 1 << ring_power
self.ring_mask:int = self.ring_size - 1
self.index_get:int = 0
self.index_put:int = 0
self.ring_data = array.array(ring_type, (0 for _ in range(self.ring_size)))
@micropython.native # @UndefinedVariable
def ring_get(self) -> int:
past_index_get = self.index_get
next_index_get = (past_index_get + 1) & self.ring_mask
if past_index_get == self.index_put:
return None # ring is empty
else:
value = self.ring_data[past_index_get]
self.index_get = next_index_get
return value
@micropython.native # @UndefinedVariable
def ring_put(self, value:int) -> int:
past_index_put = self.index_put
next_index_put = (past_index_put + 1) & self.ring_mask
if next_index_put == self.index_get:
return None # ring is full
else:
self.ring_data[past_index_put] = value
self.index_put = next_index_put
return value
"""
servo-like nema-based stepper driver based on esp32.RMT driver
"""
#
# https://github.com/micropython/micropython/issues/7015
# https://docs.micropython.org/en/latest/library/esp32.html
# https://forum.micropython.org/viewtopic.php?f=15&t=7497&start=30#p61390
#
import esp32
import micropython
from utime import sleep_us
from uasyncio import ThreadSafeFlag
from machine import Pin
from ringer import Ringer
from planner import Planner
from planner import PLAN_CMD_RAMP
from planner import PLAN_CMD_STOP
class Stepper:
def __init__(self,
pin_en:int, # stepper driver pin; "enalbe"
pin_dir:int, # stepper driver pin: "direction"
pin_step:int, # stepper driver pin: "make a step"
ringer:Ringer, # micro-program ring buffer
planner:Planner, # servo-like motion planner
rmt_channel:int=0, # rmt driver to stepper binding
invert_enable:bool=False, # init with "OFF"
invert_direction:bool=False, # init with "CCW"
delay_enable_us:int=10, # stepper driver conditioning
delay_direction_us:int=5, # stepper driver conditioning
):
self.pin_en = Pin(pin_en, mode=Pin.OUT, value=int(invert_enable))
self.pin_dir = Pin(pin_dir, mode=Pin.OUT, value=int(invert_direction))
self.pin_step = Pin(pin_step, mode=Pin.OUT, value=0)
self.invert_enable = invert_enable
self.invert_direction = invert_direction
self.delay_enable_us = delay_enable_us
self.delay_direction_us = delay_direction_us
self.ringer = ringer
self.planner = planner
self.event_cmd_ramp = ThreadSafeFlag() # motion ramp start event
self.event_cmd_stop = ThreadSafeFlag() # motion program finish event
self.event_cmd_trap = ThreadSafeFlag() # motion program error detector
self.transmit_function = self.transmit_reactor # fun-ref to avoid memory allocation inside isr
self.rmt_driver = esp32.RMT(
id=rmt_channel,
pin=self.pin_step,
# source_freq=80_000_000, # fixed in driver
clock_div=80, # 1 micro second time unit
idle_level=0, # initial signal level
tx_carrier=None, # do not chop signal
)
self.rmt_driver.loop(False) # actually: enable interrupt for "transmit ready" isr
self.rmt_driver.store_pulses(self.planner.make_item_list()) # persist ramp block patterns
async def await_cmd_ramp(self) -> None:
await self.event_cmd_ramp.wait()
async def await_cmd_stop(self) -> None:
await self.event_cmd_stop.wait()
async def await_cmd_trap(self) -> None:
await self.event_cmd_trap.wait()
def make_enable(self, on:bool) -> None:
self.pin_en.value(int(on ^ self.invert_enable))
sleep_us(self.delay_enable_us)
def make_direction(self, on:bool) -> None:
self.pin_dir.value(int(on ^ self.invert_direction))
sleep_us(self.delay_direction_us)
def persist_motion_plan(self, plan_rotate:list[int]) -> None:
"populate ring buffer with micro commands"
for value in plan_rotate:
result = self.ringer.ring_put(value)
assert result is not None # buffer not full
def make_rotation_one(self) -> None:
"accelerate then decelerate during single drive turn"
plan_one = self.planner.make_plan_rotate(+1, 0.5)
plan_two = self.planner.make_plan_rotate(-1, 0.5)
plan_full = plan_one + plan_two + [PLAN_CMD_STOP]
# print(f"{plan_full=}")
self.persist_motion_plan(plan_full)
self.transmit_reactor() # start transmit with isr self call
def make_rotation_start(self) -> None:
pass # TODO
def make_rotation_finish(self) -> None:
pass # TODO
@micropython.native # @UndefinedVariable
def transmit_reactor(self):
"""
function to execute stepper micro-program:
* invoked by self "make rotation" methods for motion start
* invoked by esp32.RMT driver "transmit ready" ISR to continue motion
note: use isr rules https://docs.micropython.org/en/latest/reference/isr_rules.html
"""
buffer = self.ringer
header = buffer.ring_get() # micro-command prefix
if header == PLAN_CMD_RAMP:
# micro-command parameters
item_index = buffer.ring_get()
item_count = buffer.ring_get()
clock_div = buffer.ring_get()
# start pulse sequence form rmt driver store
self.rmt_driver.issue_pulses(# non blocking invocation
self.transmit_function, # this is isr setup to self
item_index, # place in the store
item_count, # pulse ramp block size
clock_div, # frequency for this block
)
self.event_cmd_ramp.set()
return
if header == PLAN_CMD_STOP:
self.event_cmd_stop.set()
return
self.event_cmd_trap.set() # should not happen
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment