БИБЛИОТЕКА ДЛЯ ШАГОВОГО ДВИГАТЕЛЯ ARDUINO

Для подключения шаговых моторов к Arduino нужно использовать драйверы. Очень дешёвые и популярные моторы 28byj-48-5v часто продаются вместе со своим драйвером (транзисторная сборка ULN2003), подключить можно к любым 4-м пинам Ардуино и использовать.

Для работы с большими шаговиками (типа Nema 17) нужно использовать специализированные драйверы, ниже вы найдёте описания и схемы подключения для A4988, DRV8825 и TMC2208, драйверы такого формата подключаются и работают практически одинаково, т.к. разработаны для CNC шилдов и взаимозаменяемы. У этих драйверов нужно настроить ток при помощи крутилки на плате. Это можно сделать “на глаз”, заставив мотор вращаться и регулируя крутилку. Мотор должен вращаться, но не вибрировать как перфоратор и сильно не нагреваться. Лучше настроить ток по опорному напряжению Vref, у каждого драйвера оно считается по своей формуле (см. картинки ниже). Берём ток своего мотора из описания,  подставляем в формулу вместо current, считаем, и накручиваем полученное напряжение крутилкой. Для измерения опорного напряжения нужно подключить щупы вольтметра к самой крутилке и пину GND.

Главное преимущество дорогущих драйверов TMC – отсутствие шума/свиста/вибраций при работе, так как драйвер своими силами интерполирует сигнал до микрошага 1/256.

БИБЛИОТЕКА GYVERSTEPPER

GyverStepper – производительная библиотека для управления шаговыми моторами

  • Поддержка 4х фазных (шаг и полушаг) и STEP-DIR драйверов
  • Автоматическое отключение питания при достижении цели
  • Режимы работы:
    • Вращение с заданной скоростью
    • Следование к позиции с ускорением и ограничением скорости
    • Следование к позиции с заданной скоростью (без ускорения)
  • Быстрый алгоритм управления шагами
  • Два алгоритма плавного движения:
    • Модифицированный планировщик из библиотеки AccelStepper: максимальная плавность и скорость до 7’000 шагов/сек с ускорением (для активации пропиши дефайн SMOOTH_ALGORITHM)
    • Мой планировщик обеспечивает максимальную производительность: скорость до 30’000 шагов/сек с ускорением (активен по умолчанию). Т.е. на небольшой скорости экономит кучу процессорного времени для других задач.

Поддерживаемые платформы: все Arduino (используются стандартные Wiring-функции)

Версия 1.1: добавлена возможность плавно менять скорость в режиме KEEP_SPEED. Добавлены примеры multiStepper и accelDeccelButton
Версия 1.2: добавлена поддержка ESP и других Ардуино-совместимых плат
Версия 1.3: исправлена логика setTarget(val, RELATIVE)
Версия 1.4: добавлена задержка между STEP HIGH и STEP LOW

ДОКУМЕНТАЦИЯ


Инициализация


Библиотека поддерживает два типа драйверов:

  • STEPPER2WIRE – специализированный 2-х проводной драйвер для шагового мотора с протоколом STEP-DIR, например A4988, DRV8825, TMC2208 и прочие.
  • STEPPER4WIRE и STEPPER4WIRE_HALF – 4-х проводной драйвер, т.е. полномостовой (например L298N) или транзисторная сборка (например ULN2003).
    • STEPPER4WIRE управляет мотором в полношаговом режиме (выше скорость и момент).
    • STEPPER4WIRE_HALF – в полушаговом (меньше скорость и момент, но больше шагов на оборот и выше точность).

При инициализации указывается тип драйвера, количество шагов на оборот и пины:

  • GStepper< STEPPER2WIRE> stepper(steps, step, dir); // драйвер step-dir
  • GStepper< STEPPER2WIRE> stepper(steps, step, dir, en); // драйвер step-dir + пин enable
  • GStepper< STEPPER4WIRE> stepper(steps, a1, a2, b1, b2); // драйвер 4 пин
  • GStepper< STEPPER4WIRE> stepper(steps, a1, a2, b1, b2, en); // драйвер 4 пин + enable
  • GStepper< STEPPER4WIRE_HALF> stepper(steps, a1, a2, b1, b2); // драйвер 4 пин полушаг
  • GStepper< STEPPER4WIRE_HALF> stepper(steps, a1, a2, b1, b2, en); // драйвер 4 пин полушаг + enable

Где steps – количество шагов на один оборот вала для расчётов с градусами, step, dir, a1, a2, b1, b2 – любые GPIO на МК, en – пин отключения драйвера EN, любой GPIO на МК. Пин en опциональный, можно не указывать.

Для 4-х пиновых драйверов: a1 и a2 – первая обмотка (первая фаза), b1 и b2 – вторая обмотка (вторая фаза). При использовании мотора 28byj-48 с родным драйвером нужно поменять крайние пины местами (например, подключаем D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе меняем 5 и 2: stepper(2048, 5, 3, 4, 2);, потому что на драйвере фазы выведены через одну, вот картинка). При подключении через мостовой драйвер – подключать и указывать пины по порядку выхода фаз из мотора (см. последнюю схему выше).

Количество шагов на оборот нужно для работы функций, которые устанавливают или читают параметр в градусах. Если они не нужны – количество шагов можно поставить любое (единичку). Если нужно – количество шагов нужно указывать с учётом редукторов и микрошагов:

  • Пример 1: есть мотор NEMA 17, он имеет 200 полных шагов на оборот (по документации). Подключен через драйвер с настроенным микрошагом 1/16. При создании объекта библиотеки нужно указать 200*16 шагов.
  • Пример 2: есть мотор 28byj-48-5v, имеет 32 полных шага на оборот и редуктор с соотношением 63.68395:1. Подключен через микросхему ULN2003. Итоговое количество шагов на оборот составляет 63.68395*32 == 2038 для режима полного шага (STEPPER4WIRE).
  • Пример 3: подключим тот же самый мотор 28byj-48-5v, но в режиме полушага (STEPPER4WIRE_HALF). Количество шагов на оборот удвоится (32*2 == 64) и, с учётом редуктора, станет равным 4076.

Время шага [NEW!]


Для драйверов STEP-DIR сделана задержка между переключением состояния пина STEP, эта задержка является минимальной, т.е. она может быть больше, чем нужно, но если будет меньше – возможна нестабильная работа драйвера. По умолчанию она составляет 4 микросекунды, но разным драйверам она нужна разная (для других драйверов см. даташит):

  • A4988 – 1 мкс
  • DRV8825 – 4 мкс
  • TB6500 – 1 мкс

Также увеличение задержки может повысить стабильность работы при использовании длинных неэкранированных проводов от микроконтроллера к драйверу (к пину STEP).

Для изменения величины задержки сделай дефайн DRIVER_STEP_TIME перед подключением библиотеки:

#define DRIVER_STEP_TIME 10  // меняем задержку на 10 мкс
#include "GyverStepper.h"

Тик и тайминги


Самый главный метод библиотеки – tick(), при активной работе мотора его нужно вызывать как можно чаще. Тик имеет встроенный таймер на micros() и работает по нему. Если в коде программы присутствуют задержки на большее время, чем нужно мотору на текущей скорости, скорость мотора будет ограничена этой задержкой.

Узнать минимальный период вызова tick() (при установленной скорости) можно при помощи getMinPeriod(), который вернёт его в микросекундах. Также можно напрямую опрашивать переменную stepTime, в которой хранится текущий период. Эти инструменты можно использовать для организации работы шаговика в прерывании таймера (см. пример timerISR).

Также .tick() возвращает true, если мотор движется к цели или крутится по KEEP_SPEED и false, если мотор остановлен или приехал.

Метод getState() возвращает текущее состояние мотора аналогично tick().

Смена направления


Можно глобально (для всех режимов) сменить направление вращения мотора при помощи reverse(true).

Режимы работы


Библиотека имеет два режима работы с мотором, устанавливается при помощи setRunMode(mode), где mode:

  • FOLLOW_POS – режим плавного движения к заданной позиции с ускорением и ограничением скорости.
  • KEEP_SPEED – режим вращения с заданной скоростью (знак скорости задаёт направление вращения).

Режим FOLLOW_POS


В этом режиме мотор следует на указанную позицию в шагах или градусах. Для её установки есть следующие методы:

  • setTarget(pos) – установка абсолютной целевой позиции в шагах, принимает положительные и отрицательные значения (тип данных long).
  • setTarget(pos, type) – то же самое, но можно указать тип позиции type – абсолютная ABSOLUTE или относительная RELATIVE.
  • setTargetDeg(pos) – установка абсолютной целевой позиции в градусах, принимает положительные и отрицательные дробные значения (тип данных float).
  • setTargetDeg(pos, type) – то же самое, но можно указать тип позиции type – абсолютная ABSOLUTE или относительная RELATIVE.

Примечание: абсолютная позиция – говоришь мотору повернуться на 300 шагов, он повернётся на позицию 300. При повторном вызове  ничего не произойдёт. Относительная – говоришь повернуться на 300 – он повернётся на 300 относительно текущей позиции. Если вызвать ещё раз через некоторое время – цель сместится относительно текущей позиции вала.

Установленную целевую позицию можно прочитать:

  • getTarget() – возвращает тип данных long
  • getTargetDeg() – возвращает тип данных float

Дополнительно можно настроить максимальную скорость и ускорение при движении к целевой позиции:

  • setMaxSpeed(speed) – установка максимальной скорости по модулю в шагах/секунду, тип данных int. По умолчанию 300.
  • setMaxSpeedDeg(speed) – установка максимальной скорости по модулю в градусах/секунду, тип данных int.
  • setAcceleration(accel) – установка ускорения по модулю в шагах/сек/сек, тип данных float. По умолчанию 300.
  • setAccelerationDeg(accel) – установка ускорения по модулю в градусах/сек/сек, тип данных float.

Примечание: при установке ускорения в ноль 0 мотор будет двигаться к позиции с максимальной скоростью, заданной в setMaxSpeed().

Также можно вручную установить текущую позицию мотора в шагах и градусах при помощи:

  • setCurrent(long pos);
  • setCurrentDeg(float pos);

И прочитать её:

  • getCurrent();
  • getCurrentDeg();

Режим KEEP_SPEED


В этом режиме мотор просто крутится с заданной скоростью. Скорость задаётся при помощи

  • setSpeed(speed) – в шагах/секунду, положительные и отрицательные целые значения, тип данных int.
  • setSpeedDeg(speed) – в градусах/секунду, положительные и отрицательные дробные значения, тип данных float.

(New!) Вторым аргументом можно передать включение плавного изменения скорости, по умолчанию стоит false (NO_SMOOTH). Смотри пример accelDeccelButton

  • setSpeed(speed, smooth) – в шагах/секунду, положительные и отрицательные целые значения, тип данных int. smoothSMOOTH или NO_SMOOTH
  • setSpeedDeg(speed, smooth) – в градусах/секунду, положительные и отрицательные дробные значения, тип данных float. smoothSMOOTH или NO_SMOOTH

Установленную скорость можно прочитать:

  • getSpeed() – возвращает тип данных int
  • getSpeedDeg() – возвращает тип данных float

Алгоритм планировщика скорости


В библиотеке реализовано два алгоритма планирования скорости для режима плавного движения к позиции с ненулевым ускорением:

  • Мой алгоритм: скорость планируется с фиксированным периодом, что сильно разгружает процессор и позволяет работать на скоростях до 30’000 шагов в секунду (полностью загрузив процессор) без наличия посторонних задержек в коде. Сильная экономия процессорного времени оставляет возможность спокойно выполнять параллельно другой код и управлять несколькими моторами в разных режимах на хороших скоростях, и “ещё останется”. Немного “резковат” при торможении. Активен по умолчанию.
  • Модифицированный алгоритм из библиотеки AccelStepper: скорость планируется каждый шаг, что очень сильно нагружает процессор и ограничивает скорость до 7’000 шагов в секунду (полностью загрузив процессор) без наличия посторонних задержек в коде (в оригинальной библиотеке – 5’000 шагов/сек). Разгоняется и тормозит максимально плавно. Для активации нужно прописать дефайн #define SMOOTH_ALGORITHM перед подключением библиотеки в коде (см. пример smoothAlgorithm) или раскомментировать данный дефайн в файле библиотеки GyverStepper.h, находится сразу после описания.

Остановка и сброс


  • stop() – плавная остановка с заданным в setAcceleration() ускорением от текущего положения мотора. Можно вызвать в режиме KEEP_SPEED для плавной остановки вращения! Смотри пример accelDeccelButton
  • brake() – резкая остановка мотора. Если активен autoPower(true) – мотор будет отключен.
  • reset()brake() + сброс текущей позиции в 0. Удобно для остановки и калибровки начала координат по концевику (смотри пример endSwitch).

Управление питанием


Питанием мотора/драйвера можно управлять вручную при помощи enable() и disable(). Данные методы включают и выключают пин Enable (если он указан при инициализации), а также снимают и возвращают питание на управляющие выводы (для 4х пинового драйвера).

Поведением пина EN (если он указан при инициализации) можно управлять при помощи invertEn(true) и invertEn(false). По умолчанию установлено enable(false) переводит пин en в низкое состояние.

В библиотеке реализовано автоматическое управление питанием, включается при помощи autoPower(true), по умолчанию оно отключено. В режиме FOLLOW_POS при достижении целевой позиции мотор будет автоматически отключен (будет вызван disable()). При дальнейшей установке новой позиции мотор будет автоматически включен (будет вызван enable()).

// Примечание: далее по тексту под "по умолчанию" имеется в виду "даже если не вызывать функцию"

// Создание объекта
// steps - шагов на один оборот вала (для расчётов с градусами)
// step, dir, pin1, pin2, pin3, pin4 - любые GPIO
// en - пин отключения драйвера, любой GPIO
GStepper stepper(steps, step, dir);						// драйвер step-dir
GStepper stepper(steps, step, dir, en);					// драйвер step-dir + пин enable
GStepper stepper(steps, pin1, pin2, pin3, pin4);			// драйвер 4 пин
GStepper stepper(steps, pin1, pin2, pin3, pin4, en);		// драйвер 4 пин + enable
GStepper stepper(steps, pin1, pin2, pin3, pin4);		// драйвер 4 пин полушаг
GStepper stepper(steps, pin1, pin2, pin3, pin4, en);	// драйвер 4 пин полушаг + enable

// Здесь происходит движение мотора, вызывать как можно чаще!
// Имеет встроенный таймер
// Возвращает true, если мотор движется к цели или крутится по KEEP_SPEED
bool tick();

// Инвертировать направление мотора - true (по умолч. false)
void reverse(bool dir);

// инвертировать поведение EN пина - true (по умолч. false)
void invertEn(bool rev);

// Установка режима работы, mode:
// FOLLOW_POS - следование к позиции setTarget(...)
// KEEP_SPEED - удержание скорости setSpeed(...)
void setRunMode(GS_runMode mode);

// Установка текущей позиции мотора в шагах и градусах
void setCurrent(long pos);
void setCurrentDeg(float pos);

// Чтение текущей позиции мотора в шагах и градусах
long getCurrent();
float getCurrentDeg();

// установка целевой позиции в шагах и градусах (для режима FOLLOW_POS)
// type - ABSOLUTE или RELATIVE, по умолчанию стоит ABSOLUTE
void setTarget(long pos);
void setTarget(long pos, GS_posType type);
void setTargetDeg(float pos);
void setTargetDeg(float pos, GS_posType type);

// Получение целевой позиции в шагах и градусах
long getTarget();
float getTargetDeg();

// Установка максимальной скорости (по модулю) в шагах/секунду и градусах/секунду (для режима FOLLOW_POS)
// по умолч. 300
void setMaxSpeed(int speed);
void setMaxSpeedDeg(float speed);

// Установка ускорения в шагах и градусах в секунду (для режима FOLLOW_POS).
// При значении 0 ускорение отключается и мотор работает 
// по профилю постоянной максимальной скорости setMaxSpeed().
// По умолч. 300
void setAcceleration(int accel);
void setAccelerationDeg(float accel);

// Автоотключение EN при достижении позиции - true (по умолч. false).
void autoPower(bool mode);

// Плавная остановка с заданным ускорением от текущего положения.
// Режим будет переключен на FOLLOW_POS
// Установленная максимальная скорость будет изменена!!!
void stop();

// Жёсткая остановка
void brake();

// Жёсткая остановка + сброс позиции в 0 (для концевиков)
void reset();

// Установка целевой скорости в шагах/секунду и градусах/секунду (для режима KEEP_SPEED)
void setSpeed(int speed);
void setSpeedDeg(float speed);

// Получение целевой скорости в шагах/секунду и градусах/секунду (для режима KEEP_SPEED)
int getSpeed();
float getSpeedDeg();

// Включить мотор (пин EN)
void enable();

// Выключить мотор (пин EN)
void disable();

// Возвращает то же самое, что tick, т.е. крутится мотор или нет
bool getState();

// Возвращает минимальный период тика мотора в микросекундах при настроенной setMaxSpeed() скорости.
// Можно использовать для настройки прерываний таймера, в обработчике которого будет лежать tick() (см. пример timerISR)
uint16_t getMinPeriod();

// Текущий период "тика" для отладки и всего такого
uint16_t stepTime;

ПРИМЕРЫ


// демо - основные возможности библиотеки

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

// создание объекта
// steps - шагов на один оборот вала (для расчётов с градусами)
// step, dir, pin1, pin2, pin3, pin4 - любые GPIO
// en - пин отключения драйвера, любой GPIO
//GStepper< STEPPER2WIRE> stepper(steps, step, dir); // драйвер step-dir
//GStepper< STEPPER2WIRE> stepper(steps, step, dir, en); // драйвер step-dir + пин enable
//GStepper< STEPPER4WIRE> stepper(steps, pin1, pin2, pin3, pin4); // драйвер 4 пин
//GStepper< STEPPER4WIRE> stepper(steps, pin1, pin2, pin3, pin4, en); // драйвер 4 пин + enable
//GStepper< STEPPER4WIRE_HALF> stepper(steps, pin1, pin2, pin3, pin4); // драйвер 4 пин полушаг
//GStepper< STEPPER4WIRE_HALF> stepper(steps, pin1, pin2, pin3, pin4, en); // драйвер 4 пин полушаг + enable

void setup() {
  Serial.begin(115200);
  // режим поддержания скорости
  stepper.setRunMode(KEEP_SPEED);

  // можно установить скорость
  stepper.setSpeed(120);    // в шагах/сек
  stepper.setSpeedDeg(80);  // в градусах/сек

  // режим следования к целевй позиции
  stepper.setRunMode(FOLLOW_POS);

  // можно установить позицию
  stepper.setTarget(-2024);    // в шагах
  stepper.setTargetDeg(-360);  // в градусах

  // установка макс. скорости в градусах/сек
  stepper.setMaxSpeedDeg(400);
  
  // установка макс. скорости в шагах/сек
  stepper.setMaxSpeed(400);

  // установка ускорения в градусах/сек/сек
  stepper.setAccelerationDeg(300);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(300);

  // отключать мотор при достижении цели
  stepper.autoPower(true);

  // включить мотор (если указан пин en)
  stepper.enable();
}

void loop() {
  // просто крутим туды-сюды
  if (!stepper.tick()) {
    static bool dir;
    dir = !dir;
    stepper.setTarget(dir ? -1024 : 1024);
  }
}
// крутим мотор туда-сюда плавно с ускорением

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2); 
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  Serial.begin(115200);

  // режим следования к целевй позиции
  stepper.setRunMode(FOLLOW_POS);

  // установка макс. скорости в шагах/сек
  stepper.setMaxSpeed(400);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(500);
}

void loop() {
  // просто крутим туды-сюды
  if (!stepper.tick()) {
    static bool dir;
    dir = !dir;
    stepper.setTarget(dir ? -400 : 400);
  }

  // график положения
  static uint32_t tmr2;
  if (millis() - tmr2 > 20) {
    tmr2 = millis();
    Serial.println(stepper.getCurrent());
  }
}
// крутим мотор туда-сюда плавно с ускорением

#include "GyverStepper.h"
// подключим три мотора
// у первого и второго управление EN не подключаем
GStepper< STEPPER2WIRE> stepper1(100, 2, 3);
GStepper< STEPPER2WIRE> stepper2(100, 4, 5);
GStepper< STEPPER2WIRE> stepper3(100, 6, 7, 8);

void setup() {
  // мотор 1 просто вращается
  stepper1.setRunMode(KEEP_SPEED);
  stepper1.setSpeed(300);

  // мотор 2 будет делать sweep по проверке tick
  stepper2.setRunMode(FOLLOW_POS);
  stepper2.setMaxSpeed(1000);
  stepper2.setAcceleration(300);

  // мотор 3 будет перемещаться на случайную позицию
  stepper3.setRunMode(FOLLOW_POS);
  stepper3.setMaxSpeed(1000);
  stepper3.setAcceleration(300);
  stepper3.autoPower(true);
  stepper3.enable();
}

void loop() {
  // первый мотор
  stepper1.tick();
  
  // второй крутим туды-сюды (-1000, 1000)
  if (!stepper2.tick()) {
    static bool dir;
    dir = !dir;
    stepper2.setTarget(dir ? -1000 : 1000);
  }

  // третий по таймеру
  // будет отключаться при остановке
  stepper3.tick();
  static uint32_t tmr;
  if (millis() - tmr > 5000) {   // каждые 5 секунд
    tmr = millis();
    stepper3.setTarget(random(0, 2000));  // рандом 0-2000
  }
}
// начинаем плавный разгон при удержании кнопки. При отпускании тормозим

#include "GyverStepper.h"
GStepper< STEPPER2WIRE> stepper(800, 2, 3, 12);

void setup() {
  Serial.begin(115200);
  pinMode(A0, INPUT_PULLUP);  // кнопка на A0 и GND
  stepper.enable();
  stepper.autoPower(true);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(1200);
  stepper.setRunMode(KEEP_SPEED);
}

bool btnState = false;
void loop() {
  stepper.tick();

  // кнопка нажата
  if (!digitalRead(A0) && !btnState) {
    btnState = true;
    stepper.setSpeed(3000, SMOOTH);
  }

  // кнопка отпущена
  if (digitalRead(A0) && btnState) {
    btnState = false;
    stepper.stop();
  }
}
// крутимся с заданной скоростью

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  stepper.setRunMode(KEEP_SPEED); // режим поддержания скорости
  stepper.setSpeedDeg(50);        // в градусах/сек
}

void loop() {
  stepper.tick();
}
// установка позиции потенциометром

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  Serial.begin(115200);
  stepper.setRunMode(FOLLOW_POS);   // режим следования к целевй позиции
  stepper.setMaxSpeed(400);         // установка макс. скорости в шагах/сек
  stepper.setAcceleration(500);     // установка ускорения в шагах/сек/сек

  // пусть драйвер выключается при достижении позиции
  stepper.autoPower(true);
}

void loop() {
  stepper.tick();

  // сделаем таймер на 20 мс
  // будем опрашивать потенциометр и строить графики
  static uint32_t tmr2;
  if (millis() - tmr2 > 20) {
    tmr2 = millis();
    static float val;
    // потенциометр на A0
    // фильтруем, иначе мотор будет трястись
    val += (analogRead(0) - val) * 0.08;

    stepper.setTarget(val);     // ставим новую позицию
    Serial.print(stepper.getTarget());
    Serial.print(',');
    Serial.println(stepper.getCurrent());
  }
}
// установка скорости потенциометром

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  stepper.setRunMode(KEEP_SPEED); // режим поддержания скорости
  stepper.setSpeedDeg(50);        // в градусах/сек
}

void loop() {
  stepper.tick();

  // сделаем таймер на 50 мс и будем опрашивать потенциометр
  // менять скорость чаще нет смысла
  static uint32_t tmr2;
  if (millis() - tmr2 > 50) {
    tmr2 = millis();

    // ставим новую скорость (-512.. 512 шагов в секунду)
    // будет крутиться в разные стороны
    stepper.setSpeed(512 - analogRead(0));
  }
}
// пример работы stop()
// на графике будет видно, как сместилась установка и мотор к ней затормозил
#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  Serial.begin(115200);
  stepper.setMaxSpeed(400);
  stepper.setAcceleration(300);
  stepper.setRunMode(FOLLOW_POS);

  // отправляем мотор подальше
  stepper.setTarget(-2024);
}

void loop() {
  stepper.tick();

  // плавная остановка через 3 секунды
  static uint32_t tmr;
  static bool flag = false;
  if (!flag && millis() > 3000) {
    stepper.stop();
    flag = true;
  }

  // график установки и текущей позиции
  static uint32_t tmr2;
  if (millis() - tmr2 > 20) {
    tmr2 = millis();
    Serial.print(stepper.getTarget());
    Serial.print(',');
    Serial.println(stepper.getCurrent());
  }
}
// пример с концевиком
#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  // наша задача - при запуске крутить мотор в сторону до нажатия на кнопку
  pinMode(12, INPUT_PULLUP);  // кнопка на D12 и GND
  
  stepper.setRunMode(KEEP_SPEED);
  stepper.setSpeedDeg(-10);   // медленно крутимся НАЗАД

  // пока кнопка не нажата
  while(digitalRead(12)) {    
    stepper.tick();
  }
  // вот тут кнопка нажата, сразу вырубаем мотор.
  // Текущее положение также сбрасывается в 0
  stepper.reset();

  // дальше например врубаем FOLLOW_POS
  stepper.setRunMode(FOLLOW_POS);
}

void loop() {
  // и качаемся в 20 шагах от кнопки и до 300
  static bool dir;
  if (!stepper.tick()) {
    dir = !dir;
    stepper.setTarget(dir ? 20 : 300);
  }
}
// крутим мотор туда-сюда плавно с ускорением
// драйвер STEP-DIR

#include "GyverStepper.h"
GStepper< STEPPER2WIRE> stepper(800, 2, 3, 4);
// 2 - STEP
// 3 - DIR
// 4 - EN

void setup() {
  // режим следования к целевй позиции
  stepper.setRunMode(FOLLOW_POS);

  // установка макс. скорости в шагах/сек
  stepper.setMaxSpeed(1000);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(1000);
}

int val = 2000;
void loop() {
  if (!stepper.tick()) {
    val = -val;
    stepper.setTarget(val);
  }
}
// используем более плавный алгоритм движения. Макс. скорость ограничена до
// 7000 шаг/сек, алгоритм использует много процессорного времени!

// перед подключением библиотеки дефайним
#define SMOOTH_ALGORITHM

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

void setup() {
  Serial.begin(115200);

  // режим следования к целевй позиции
  stepper.setRunMode(FOLLOW_POS);

  // установка макс. скорости в шагах/сек
  stepper.setMaxSpeed(400);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(500);
}

void loop() {
  // просто крутим туды-сюды
  if (!stepper.tick()) {
    static bool dir;
    dir = !dir;
    stepper.setTarget(dir ? -400 : 400);
  }
}
// пример с тиком по прерыванию таймера
// используется GyverTimers

#include "GyverStepper.h"
GStepper< STEPPER4WIRE> stepper(2048, 5, 3, 4, 2);
// мотор с драйвером ULN2003 подключается по порядку пинов, но крайние нужно поменять местами
// то есть у меня подключено D2-IN1, D3-IN2, D4-IN3, D5-IN4, но в программе поменял 5 и 2

#include "GyverTimers.h"

void setup() {
  Serial.begin(115200);

  // режим следования к целевй позиции
  stepper.setRunMode(FOLLOW_POS);

  // установка макс. скорости в шагах/сек
  stepper.setMaxSpeed(400);

  // установка ускорения в шагах/сек/сек
  stepper.setAcceleration(500);

  // настраиваем прерывания с периодом, при котором 
  // система сможет обеспечить максимальную скорость мотора.
  // Для большей плавности лучше лучше взять период чуть меньше, например в два раза
  Timer2.setPeriod(stepper.getMinPeriod() / 2);

  // взводим прерывание
  Timer2.enableISR();
}

// обработчик
ISR(TIMER2_A) {
  stepper.tick(); // тикаем тут
}

void loop() {
  // просто крутим туды-сюды
  if (!stepper.tick()) {  // тут всё равно вызываем для смены направления
    static bool dir;
    dir = !dir;
    stepper.setTarget(dir ? -400 : 400);
  }

  // график положения
  Serial.println(stepper.getCurrent());

  // задержка, чтобы показать работу степпера в прерывании  
  delay(100);
}

УСТАНОВКА БИБЛИОТЕКИ

Если вы не знаете, как установить библиотеку – читайте отдельный урок по работе с библиотеками!

БАГИ И ОШИБКИ

Если вы нашли баг или ошибку в исходнике или примерах, или у вас есть идеи по доработке библиотеки – пишите пожалуйста на почту alex@alexgyver.ru. В комментарии на страницах я заглядываю очень редко, на форум – ещё реже.

ОСТАЛЬНЫЕ БИБЛИОТЕКИ

У меня есть ещё очень много всего интересного! Смотрите полный список библиотек вот здесь.