mirror of
https://github.com/GyverLibs/GyverMotor2.git
synced 2026-06-05 14:47:00 +03:00
add
This commit is contained in:
+265
@@ -0,0 +1,265 @@
|
||||
#pragma once
|
||||
#include <Arduino.h>
|
||||
|
||||
enum class GM2 : uint8_t {
|
||||
ONLY_PWM, // один ШИМ (PWM)
|
||||
DIR_DIR, // без ШИМ (dir + dir)
|
||||
DIR_PWM, // один ШИМ без инверсии (dir + PWM)
|
||||
DIR_PWM_INV, // один ШИМ с инверсией (dir + ~PWM)
|
||||
PWM_PWM_SPEED, // два ШИМ, режим скорости (PWM + PWM)
|
||||
PWM_PWM_POWER, // два ШИМ, режим момента (~PWM + ~PWM)
|
||||
DIR_DIR_PWM, // два направления и ШИМ (dir + dir + PWM)
|
||||
};
|
||||
|
||||
template <GM2 driver, uint8_t res = 8>
|
||||
class GyverMotor2 {
|
||||
public:
|
||||
// инициализация с указанием типа драйвера, разрешения ШИМ (бит) и пинов
|
||||
GyverMotor2(uint8_t pinA, uint8_t pinB = 0xff, uint8_t pinC = 0xff) : _pinA(pinA), _pinB(pinB), _pinC(pinC) {
|
||||
pinMode(_pinA, OUTPUT);
|
||||
if (driver != GM2::ONLY_PWM) pinMode(_pinB, OUTPUT);
|
||||
if (driver == GM2::DIR_DIR_PWM) pinMode(_pinC, OUTPUT);
|
||||
_setAll(0);
|
||||
}
|
||||
|
||||
// установить deadtime (задержка при смене направления) в микросекундах (умолч. 0)
|
||||
void setDeadtime(uint8_t us) {
|
||||
_deadtime = us;
|
||||
}
|
||||
|
||||
// получить deadtime в микросекундах
|
||||
uint8_t getDeadTime() const {
|
||||
return _deadtime;
|
||||
}
|
||||
|
||||
// установить реверс направления (умолч. false)
|
||||
void setReverse(bool rev) {
|
||||
_rev = rev;
|
||||
_run(_speed);
|
||||
}
|
||||
|
||||
// получить реверс направления
|
||||
bool getReverse() const {
|
||||
return _rev;
|
||||
}
|
||||
|
||||
// установить минимальный ШИМ (умолч. 0)
|
||||
void setMinDuty(uint16_t duty) {
|
||||
_minDuty = (duty > _maxDuty) ? _maxDuty : duty;
|
||||
_run(_speed);
|
||||
}
|
||||
|
||||
// установить минимальный ШИМ в % от максимального (умолч. 0)
|
||||
void setMinDutyPerc(uint8_t perc) {
|
||||
setMinDuty(_perc(perc));
|
||||
}
|
||||
|
||||
// получить минимальный ШИМ
|
||||
uint16_t getMinDuty() const {
|
||||
return _minDuty;
|
||||
}
|
||||
|
||||
// получить максимальный ШИМ
|
||||
uint16_t getMaxDuty() const {
|
||||
return _maxDuty;
|
||||
}
|
||||
|
||||
// установить скорость ШИМ (-макс.. макс)
|
||||
void runSpeed(int16_t speed) {
|
||||
speed = constrain(speed, -_maxDuty, _maxDuty);
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
_target = speed;
|
||||
if (!_ds) _run(speed);
|
||||
#else
|
||||
_run(speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
// установить скорость в % от максимального ШИМ (-100.. 100%)
|
||||
void runSpeedPerc(int8_t perc) {
|
||||
runSpeed(_perc(perc));
|
||||
}
|
||||
|
||||
// получить текущую скорость мотора в ШИМ
|
||||
int16_t getSpeed() const {
|
||||
return _speed;
|
||||
}
|
||||
|
||||
// получить направление: мотор крутится (1 и -1), мотор остановлен (0)
|
||||
int8_t getDir() const {
|
||||
return _speed ? (_speed > 0 ? 1 : -1) : 0;
|
||||
}
|
||||
|
||||
// остановка. Если включено ускорение, то плавная. Отключает мотор
|
||||
void stop() {
|
||||
runSpeed(0);
|
||||
}
|
||||
|
||||
// активное торможение (оставляет пины драйвера активными)
|
||||
void brake(bool active = true) {
|
||||
_setAll(active);
|
||||
_speed = 0;
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
_target = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
// остановить и отключить мотор
|
||||
void disable() {
|
||||
brake(false);
|
||||
}
|
||||
|
||||
// установить ускорение в ШИМ в секунду. Реальный минимум - 5. 0 чтобы отключить
|
||||
void setAccel(uint16_t accel) {
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
if (!accel) {
|
||||
_ds = 0;
|
||||
_prd = 0;
|
||||
} else {
|
||||
uint16_t ms = 1000 / accel;
|
||||
_prd = constrain(ms, 30, 200);
|
||||
_ds = uint32_t(accel) * _prd / 1000;
|
||||
_ds = constrain(_ds, 1, _maxDuty);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// установить ускорение в процентах в секунду. 0 чтобы отключить
|
||||
void setAccelPerc(uint8_t perc) {
|
||||
setAccel(_perc(perc));
|
||||
}
|
||||
|
||||
// получить период, не реже которого нужно вызывать tick, мс
|
||||
uint8_t getDt() const {
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
return _prd;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
// получить целевую скорость (режим ускорения)
|
||||
int16_t getTarget() const {
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
return _target;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
// плавное изменение к указанной скорости с ускорением setAccel, вызывать в loop. Вернёт true при достижении скорости
|
||||
bool tick() {
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
if (_ds && (_speed != _target) && (uint8_t(uint8_t(millis()) - _tmr) >= _prd)) {
|
||||
_tmr = millis();
|
||||
int16_t err = _target - _speed;
|
||||
_run(_speed + constrain(err, -_ds, _ds));
|
||||
return _speed == _target;
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
private:
|
||||
void _run(int16_t duty) {
|
||||
if (!duty) {
|
||||
disable();
|
||||
return;
|
||||
}
|
||||
|
||||
if (_deadtime && _speed && (_speed > 0) != (duty > 0)) {
|
||||
_setAll(0);
|
||||
delayMicroseconds(_deadtime);
|
||||
}
|
||||
|
||||
_speed = duty;
|
||||
|
||||
bool dir = (duty > 0) ^ _rev;
|
||||
if (duty < 0) duty = -duty;
|
||||
if (_minDuty) duty = ((int32_t(duty) * (_maxDuty - _minDuty) + (1 << res) - 1) >> res) + _minDuty;
|
||||
|
||||
#ifdef __AVR__
|
||||
if (res > 8 && duty == 255) ++duty; // защита от 255 при разрешении > 8 бит
|
||||
#endif
|
||||
|
||||
switch (driver) {
|
||||
case GM2::ONLY_PWM:
|
||||
analogWrite(_pinA, duty);
|
||||
break;
|
||||
|
||||
case GM2::DIR_DIR:
|
||||
digitalWrite(_pinA, !dir);
|
||||
digitalWrite(_pinB, dir);
|
||||
break;
|
||||
|
||||
case GM2::DIR_PWM:
|
||||
digitalWrite(_pinA, !dir);
|
||||
analogWrite(_pinB, duty);
|
||||
break;
|
||||
|
||||
case GM2::DIR_PWM_INV:
|
||||
digitalWrite(_pinA, !dir);
|
||||
analogWrite(_pinB, dir ? duty : (_maxDuty - duty));
|
||||
break;
|
||||
|
||||
case GM2::PWM_PWM_SPEED:
|
||||
analogWrite(_pinA, dir ? 0 : duty);
|
||||
analogWrite(_pinB, dir ? duty : 0);
|
||||
break;
|
||||
|
||||
case GM2::PWM_PWM_POWER:
|
||||
analogWrite(_pinA, dir ? (_maxDuty - duty) : _maxDuty);
|
||||
analogWrite(_pinB, dir ? _maxDuty : (_maxDuty - duty));
|
||||
break;
|
||||
|
||||
case GM2::DIR_DIR_PWM:
|
||||
digitalWrite(_pinA, !dir);
|
||||
digitalWrite(_pinB, dir);
|
||||
analogWrite(_pinC, duty);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void _setAll(bool val) {
|
||||
switch (driver) {
|
||||
case GM2::ONLY_PWM:
|
||||
analogWrite(_pinA, 0);
|
||||
break;
|
||||
|
||||
case GM2::DIR_DIR:
|
||||
digitalWrite(_pinA, val);
|
||||
digitalWrite(_pinB, val);
|
||||
break;
|
||||
|
||||
case GM2::DIR_PWM:
|
||||
case GM2::DIR_PWM_INV:
|
||||
digitalWrite(_pinA, val);
|
||||
analogWrite(_pinB, val ? _maxDuty : 0);
|
||||
break;
|
||||
|
||||
case GM2::PWM_PWM_SPEED:
|
||||
case GM2::PWM_PWM_POWER:
|
||||
analogWrite(_pinA, val ? _maxDuty : 0);
|
||||
analogWrite(_pinB, val ? _maxDuty : 0);
|
||||
break;
|
||||
|
||||
case GM2::DIR_DIR_PWM:
|
||||
digitalWrite(_pinA, val);
|
||||
digitalWrite(_pinB, val);
|
||||
analogWrite(_pinC, val ? _maxDuty : 0);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const uint8_t _pinA, _pinB, _pinC;
|
||||
uint8_t _deadtime = 0;
|
||||
int16_t _minDuty = 0, _speed = 0;
|
||||
#ifndef GMOTOR2_NO_ACCEL
|
||||
int16_t _target = 0, _ds = 0;
|
||||
uint8_t _tmr = 0, _prd = 0;
|
||||
#endif
|
||||
bool _rev = 0;
|
||||
|
||||
static constexpr int16_t _maxDuty = (1 << res) - 1;
|
||||
static constexpr int16_t _perc(int8_t perc) { return int32_t(_maxDuty) * perc / 100; }
|
||||
};
|
||||
@@ -1,2 +1,227 @@
|
||||
[](https://github.com/GyverLibs/GyverMotor2/releases/latest/download/GyverMotor2.zip)
|
||||
[](https://registry.platformio.org/libraries/gyverlibs/GyverMotor2)
|
||||
[](https://alexgyver.ru/)
|
||||
[](https://alexgyver.ru/support_alex/)
|
||||
[](https://github-com.translate.goog/GyverLibs/GyverMotor2?_x_tr_sl=ru&_x_tr_tl=en)
|
||||
|
||||
[](https://t.me/GyverLibs)
|
||||
|
||||
# GyverMotor2
|
||||
Библиотека для щёточных моторов и драйверов под Arduino
|
||||
Библиотека для управления коллекторными моторами через драйвер, улучшенная версия библиотеки [GyverMotor](https://github.com/GyverLibs/GyverMotor)
|
||||
- Контроль скорости и направления вращения
|
||||
- Работа с ШИМ любого разрешения
|
||||
- Плавный пуск и изменение скорости
|
||||
- Порог минимального ШИМ
|
||||
- Программный deadtime
|
||||
- Поддержка 7 типов драйверов
|
||||
|
||||
### Совместимость
|
||||
Совместима со всеми Arduino платформами (используются Arduino-функции)
|
||||
|
||||
## Содержание
|
||||
- [Использование](#usage)
|
||||
- [Версии](#versions)
|
||||
- [Установка](#install)
|
||||
- [Баги и обратная связь](#feedback)
|
||||
|
||||
<a id="usage"></a>
|
||||
|
||||
## Использование
|
||||
### Тип драйвера
|
||||
| Драйвер | Описание | Пины | speed > 0 | speed < 0 | stop/disable | brake |
|
||||
|----------------------|-------------------------|-------------------|-------------|-------------|--------------|-------------|
|
||||
| `GM2::ONLY_PWM` | Только ШИМ | (PWM) | (PWM) | (PWM) | (0) | (0) |
|
||||
| `GM2::DIR_DIR` | Только направление | (GPIO, GPIO) | (0, 1) | (1, 0) | (0, 0) | (1, 1) |
|
||||
| `GM2::DIR_PWM` | Один ШИМ без инверсии | (GPIO, PWM) | (0, PWM) | (1, PWM) | (0, 0) | (1, MAX) |
|
||||
| `GM2::DIR_PWM_INV` | Один ШИМ с инверсией | (GPIO, PWM) | (0, PWM) | (1, ~PWM) | (0, 0) | (1, MAX) |
|
||||
| `GM2::PWM_PWM_SPEED` | Два ШИМ, режим скорости | (PWM, PWM) | (0, PWM) | (PWM, 0) | (0, 0) | (MAX, MAX) |
|
||||
| `GM2::PWM_PWM_POWER` | Два ШИМ, режим момента | (PWM, PWM) | (~PWM, MAX) | (MAX, ~PWM) | (0, 0) | (MAX, MAX) |
|
||||
| `GM2::DIR_DIR_PWM` | Два направления и ШИМ | (GPIO, GPIO, PWM) | (0, 1, PWM) | (1, 0, PWM) | (0, 0, 0) | (1, 1, MAX) |
|
||||
|
||||
Примечания:
|
||||
|
||||
- В скобках указаны пины в порядке конструктора, т.е. например для `DIR_PWM` инициализация будет `GyverMotor2<GM2::DIR_PWM> motor(gpio, pwm)`, где gpio - обычный цифровой пин (digitalWrite), pwm - пин с поддержкой ШИМ (analogWrite)
|
||||
- `MAX` - максимальное значение ШИМ при указанном разрешении
|
||||
- `PWM` - прямой ШИМ `(0.. MAX)`
|
||||
- `~PWM` - обратный ШИМ `(MAX.. 0)`
|
||||
|
||||
Выбор режима для H-мост драйвера (2 пина, обычно IN1 и IN2) - большинство модулей-драйверов для Arduino:
|
||||
|
||||
- Для симметричной по скорости работы в обоих направлениях рекомендуется режим с двумя ШИМ, где `PWM_PWM_SPEED` имеет более высокую скорость, а `PWM_PWM_POWER` более стабилен на низких оборотах и имеет более высокий момент на некоторых моторах и драйверах. Идеален для колёсных роботов
|
||||
- Для работы в обоих направлениях, когда симметричность работы мотора не важна, можно использовать режим `DIR_PWM_INV` - он экономит один ШИМ пин. Драйверы, которые работают с `DIR_PWM` (без инверсии), встречаются редко
|
||||
- Для работы в одну сторону с контролем скорости (MOSFET или мост с замкнутым пином) подходит режим `ONLY_PWM` и использует только один пин
|
||||
- Для релейного управления (без контроля скорости) можно использовать режим `DIR_DIR`
|
||||
|
||||
Для драйверов с раздельным управлением направлением и скоростью IN1+IN2+EN нужен режим `DIR_DIR_PWM`.
|
||||
|
||||
### Настройки компиляции
|
||||
Перед подключением библиотеки
|
||||
|
||||
```cpp
|
||||
#define GMOTOR2_NO_ACCEL // вырезать модуль ускорения
|
||||
```
|
||||
|
||||
### Описание класса
|
||||
```cpp
|
||||
// инициализация с указанием типа драйвера, разрешения ШИМ (бит) и пинов
|
||||
GyverMotor2<driver, res = 8>(uint8_t pinA, uint8_t pinB = 0xff, uint8_t pinC = 0xff);
|
||||
|
||||
// установить deadtime (задержка при смене направления) в микросекундах (умолч. 0)
|
||||
void setDeadtime(uint8_t us);
|
||||
|
||||
// получить deadtime в микросекундах
|
||||
uint8_t getDeadTime();
|
||||
|
||||
// установить реверс направления (умолч. false)
|
||||
void setReverse(bool rev);
|
||||
|
||||
// получить реверс направления
|
||||
bool getReverse();
|
||||
|
||||
// установить минимальный ШИМ (умолч. 0)
|
||||
void setMinDuty(uint16_t duty);
|
||||
|
||||
// установить минимальный ШИМ в % от максимального (умолч. 0)
|
||||
void setMinDutyPerc(uint8_t perc);
|
||||
|
||||
// получить минимальный ШИМ
|
||||
uint16_t getMinDuty();
|
||||
|
||||
// получить максимальный ШИМ
|
||||
uint16_t getMaxDuty();
|
||||
|
||||
// установить скорость ШИМ (-макс.. макс)
|
||||
void runSpeed(int16_t speed);
|
||||
|
||||
// установить скорость в % от максимального ШИМ (-100.. 100%)
|
||||
void runSpeedPerc(int8_t perc);
|
||||
|
||||
// получить текущую скорость мотора в ШИМ
|
||||
int16_t getSpeed();
|
||||
|
||||
// получить направление: мотор крутится (1 и -1), мотор остановлен (0)
|
||||
int8_t getDir();
|
||||
|
||||
// остановка. Если включено ускорение, то плавная
|
||||
void stop();
|
||||
|
||||
// активное торможение (оставляет пины драйвера активными)
|
||||
void brake();
|
||||
|
||||
// остановить и отключить мотор
|
||||
void disable();
|
||||
|
||||
// установить ускорение в ШИМ в секунду. Реальный минимум - 5. 0 чтобы отключить
|
||||
void setAccel(uint16_t accel);
|
||||
|
||||
// установить ускорение в процентах в секунду. 0 чтобы отключить
|
||||
void setAccelPerc(uint8_t perc);
|
||||
|
||||
// получить период, не реже которого нужно вызывать tick, мс
|
||||
uint8_t getDt();
|
||||
|
||||
// получить целевую скорость (режим ускорения)
|
||||
int16_t getTarget();
|
||||
|
||||
// плавное изменение к указанной скорости с ускорением setAccel, вызывать в loop. Вернёт true при достижении скорости
|
||||
bool tick();
|
||||
```
|
||||
|
||||
### Описание фич
|
||||
#### Запуск и остановка
|
||||
- `runSpeed` запускает мотор с указанной скоростью, поддерживает отрицательные значения для вращения в обратную сторону. При значении `0` отключает мотор
|
||||
- `stop` - остановка и отключение, равносильно вызову `runSpeed(0)`
|
||||
- `setReverse` - реверс мотора, при установке `true` будет вращаться в противоположную сторону
|
||||
- `brake` - активное торможение через драйвер (поддерживается не везде)
|
||||
- `disable` - остановка и отключение драйвера
|
||||
|
||||
#### DeadTime
|
||||
Внутри `runSpeed` при смене направления вращения отключает драйвер и создаёт задержку на указанное кол-во микросекунд, после чего подаёт нужный сигнал на мотор. Это нужно для самодельных простых драйверов по схеме H-мост, чтобы избежать замыкания моста. У драйверов в виде микросхем и модулей обычно есть встроенный аппаратный deadtime и в библиотеке его включать не нужно.
|
||||
|
||||
#### MinDuty
|
||||
Позволяет настроить минимальный сигнал на мотор. Значение, поданное в `runSpeed` будет линейно масштабироваться от указанного MinDuty до максимума (если не равно нулю). Это позволяет "пропустить" значения, при которых мотор не может тронуться, не меняя логику задания скорости. Пример значений для 8 бит и `MinDuty=50`:
|
||||
|
||||
| `runSpeed` | Фактический PWM |
|
||||
|------------|-----------------|
|
||||
| 0 | 0 |
|
||||
| 1 | 50 |
|
||||
| 50 | 90 |
|
||||
| 150 | 170 |
|
||||
| 200 | 210 |
|
||||
| 255 | 255 |
|
||||
|
||||
#### Accel
|
||||
При задании ненулевого ускорения (в единицах ШИМ в секунду) вызов `runSpeed` не применяет указанную скорость сразу, вместо этого скорость будет плавно меняться к заданной. Для работы нужно вызывать тикер в основном цикле программы не реже, чем `getDt` миллисекунд (варьируется от 30 до 200 в зависимости от ускорения). Вызов `stop` сделает плавную остановку, а `brake` и `disable` остановят мотор резко:
|
||||
|
||||
```cpp
|
||||
void setup() {
|
||||
motor.setAccel(80);
|
||||
motor.runSpeed(170);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
motor.tick(); // плавно разгонит мотор до скорости 170
|
||||
}
|
||||
```
|
||||
|
||||
Может пригодиться при управлении тяжёлым колёсным роботом, чтобы избежать рывков при разгоне и торможении.
|
||||
|
||||
## Примеры
|
||||
```cpp
|
||||
#include <GyverMotor2.h>
|
||||
|
||||
// GyverMotor2<GM2::DIR_DIR> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_PWM> motor(5, 6);
|
||||
GyverMotor2<GM2::DIR_PWM_INV> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_SPEED> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_POWER> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_DIR_PWM> motor(5, 6, 7);
|
||||
|
||||
void setup() {
|
||||
// motor.setDeadtime(5);
|
||||
// motor.setMinDuty(50);
|
||||
// motor.setReverse(true);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
int speed = map(analogRead(0), 0, 1023, -255, 255);
|
||||
motor.runSpeed(speed);
|
||||
}
|
||||
```
|
||||
|
||||
<a id="versions"></a>
|
||||
|
||||
## Версии
|
||||
- v1.0
|
||||
|
||||
<a id="install"></a>
|
||||
## Установка
|
||||
- Библиотеку можно найти по названию **GyverMotor2** и установить через менеджер библиотек в:
|
||||
- Arduino IDE
|
||||
- Arduino IDE v2
|
||||
- PlatformIO
|
||||
- [Скачать библиотеку](https://github.com/GyverLibs/GyverMotor2/archive/refs/heads/main.zip) .zip архивом для ручной установки:
|
||||
- Распаковать и положить в *C:\Program Files (x86)\Arduino\libraries* (Windows x64)
|
||||
- Распаковать и положить в *C:\Program Files\Arduino\libraries* (Windows x32)
|
||||
- Распаковать и положить в *Документы/Arduino/libraries/*
|
||||
- (Arduino IDE) автоматическая установка из .zip: *Скетч/Подключить библиотеку/Добавить .ZIP библиотеку…* и указать скачанный архив
|
||||
- Читай более подробную инструкцию по установке библиотек [здесь](https://alexgyver.ru/arduino-first/#%D0%A3%D1%81%D1%82%D0%B0%D0%BD%D0%BE%D0%B2%D0%BA%D0%B0_%D0%B1%D0%B8%D0%B1%D0%BB%D0%B8%D0%BE%D1%82%D0%B5%D0%BA)
|
||||
### Обновление
|
||||
- Рекомендую всегда обновлять библиотеку: в новых версиях исправляются ошибки и баги, а также проводится оптимизация и добавляются новые фичи
|
||||
- Через менеджер библиотек IDE: найти библиотеку как при установке и нажать "Обновить"
|
||||
- Вручную: **удалить папку со старой версией**, а затем положить на её место новую. "Замену" делать нельзя: иногда в новых версиях удаляются файлы, которые останутся при замене и могут привести к ошибкам!
|
||||
|
||||
<a id="feedback"></a>
|
||||
|
||||
## Баги и обратная связь
|
||||
При нахождении багов создавайте **Issue**, а лучше сразу пишите на почту [alex@alexgyver.ru](mailto:alex@alexgyver.ru)
|
||||
Библиотека открыта для доработки и ваших **Pull Request**'ов!
|
||||
|
||||
При сообщении о багах или некорректной работе библиотеки нужно обязательно указывать:
|
||||
- Версия библиотеки
|
||||
- Какой используется МК
|
||||
- Версия SDK (для ESP)
|
||||
- Версия Arduino IDE
|
||||
- Корректно ли работают ли встроенные примеры, в которых используются функции и конструкции, приводящие к багу в вашем коде
|
||||
- Какой код загружался, какая работа от него ожидалась и как он работает в реальности
|
||||
- В идеале приложить минимальный код, в котором наблюдается баг. Не полотно из тысячи строк, а минимальный код
|
||||
@@ -0,0 +1,23 @@
|
||||
#include <Arduino.h>
|
||||
#include <GyverMotor2.h>
|
||||
|
||||
// GyverMotor2<GM2::DIR_DIR> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_PWM> motor(5, 6);
|
||||
GyverMotor2<GM2::DIR_PWM_INV> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_SPEED> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_POWER> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_DIR_PWM> motor(5, 6, 7);
|
||||
|
||||
void setup() {
|
||||
// установка ускорения
|
||||
motor.setAccel(100);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// вызов тикера
|
||||
motor.tick();
|
||||
|
||||
// скорость будет применяться плавно
|
||||
int speed = map(analogRead(0), 0, 1023, -255, 255);
|
||||
motor.runSpeed(speed);
|
||||
}
|
||||
@@ -0,0 +1,20 @@
|
||||
#include <Arduino.h>
|
||||
#include <GyverMotor2.h>
|
||||
|
||||
// GyverMotor2<GM2::DIR_DIR> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_PWM> motor(5, 6);
|
||||
GyverMotor2<GM2::DIR_PWM_INV> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_SPEED> motor(5, 6);
|
||||
// GyverMotor2<GM2::PWM_PWM_POWER> motor(5, 6);
|
||||
// GyverMotor2<GM2::DIR_DIR_PWM> motor(5, 6, 7);
|
||||
|
||||
void setup() {
|
||||
// motor.setDeadtime(5);
|
||||
// motor.setMinDuty(50);
|
||||
// motor.setReverse(true);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
int speed = map(analogRead(0), 0, 1023, -255, 255);
|
||||
motor.runSpeed(speed);
|
||||
}
|
||||
@@ -0,0 +1,47 @@
|
||||
#######################################
|
||||
# Syntax Coloring Map For GyverMotor2
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
GyverMotor2 KEYWORD1
|
||||
GM2 KEYWORD1
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
|
||||
setDeadtime KEYWORD2
|
||||
getDeadTime KEYWORD2
|
||||
setReverse KEYWORD2
|
||||
getReverse KEYWORD2
|
||||
setMinDuty KEYWORD2
|
||||
setMinDutyPerc KEYWORD2
|
||||
getMinDuty KEYWORD2
|
||||
getMaxDuty KEYWORD2
|
||||
runSpeed KEYWORD2
|
||||
runSpeedPerc KEYWORD2
|
||||
getSpeed KEYWORD2
|
||||
getDir KEYWORD2
|
||||
stop KEYWORD2
|
||||
brake KEYWORD2
|
||||
disable KEYWORD2
|
||||
setAccel KEYWORD2
|
||||
setAccelPerc KEYWORD2
|
||||
getDt KEYWORD2
|
||||
getTarget KEYWORD2
|
||||
tick KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
|
||||
ONLY_PWM LITERAL1
|
||||
DIR_DIR LITERAL1
|
||||
DIR_PWM LITERAL1
|
||||
DIR_PWM_INV LITERAL1
|
||||
PWM_PWM_SPEED LITERAL1
|
||||
PWM_PWM_POWER LITERAL1
|
||||
DIR_DIR_PWM LITERAL1
|
||||
@@ -0,0 +1,9 @@
|
||||
name=GyverMotor2
|
||||
version=1.0.0
|
||||
author=AlexGyver <alex@alexgyver.ru>
|
||||
maintainer=AlexGyver <alex@alexgyver.ru>
|
||||
sentence=Library for motor driver control
|
||||
paragraph=Library for motor driver control
|
||||
category=Device Control
|
||||
url=https://github.com/GyverLibs/GyverMotor2
|
||||
architectures=*
|
||||
Reference in New Issue
Block a user