Skip to content

Commit

Permalink
дефайн существования
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexGyver committed Dec 21, 2020
1 parent 5ced9d6 commit 92a5ad7
Show file tree
Hide file tree
Showing 73 changed files with 918 additions and 1,568 deletions.
67 changes: 29 additions & 38 deletions AccelMotor/AccelMotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,28 +23,6 @@ bool AccelMotor::tick(long pos) {
controlSpeed = constrain(controlSpeed, -_maxSpeed, _maxSpeed);
controlPos += controlSpeed * _dts;
}
/*
// старый алгоритм
if (err != 0) {
float accelDt = _accel * _dts;
float accel = accelDt;
if (abs(err) < _stopzone && abs(_lastSpeed - controlSpeed) < 2) { // условие завершения движения
controlPos = _targetPos;
controlSpeed = 0;
accel = 0;
}
if (abs(err) < (float)(controlSpeed * controlSpeed) / (2.0 * accelDt)) { // если пора тормозить
err = -err; // разворачиваем ускорение
accel = (float)(controlSpeed * controlSpeed) / (2.0 * abs(err)); // пересчёт ускорения для плавности
if (_sign(controlSpeed) == _sign(err)) err = -err; // поворачивай обратно
}
controlSpeed += accel * _sign(err); // применяем ускорение
controlSpeed = constrain(controlSpeed, -_maxSpeed*_dts, _maxSpeed*_dts); // ограничим
controlPos += controlSpeed; // двигаем позицию
_lastSpeed = controlSpeed;
}
*/
PIDcontrol(controlPos, _currentPos, true);
}
break;
Expand All @@ -71,21 +49,34 @@ bool AccelMotor::tick(long pos) {

void AccelMotor::PIDcontrol(long target, long current, bool cutoff) {
// cutoff нужен только для стабилизации позиции, обнуляет integral и учитывает мёртвую зону мотора
long err = target - current;
_dutyF = err * kp; // P составляющая
_dutyF += (float)(_prevInput - current) * kd / _dts; // D составляющая
_prevInput = current;
integral += (float)err * ki * _dts;
_dutyF += integral; // I составляющая
if (cutoff) { // отсечка
if (abs(err) > _stopzone) _dutyF += _sign(err)*_minDuty; // учитываем _minDuty - мёртвую зону мотора (метод setMinDuty)
else integral = 0;
} else {
long err = target - current; // ошибка регулирования
long deltaInput = _prevInput - current; // изменение входного сигнала
_dutyF = 0;
if (!cutoff) _dutyF = err * kp; // P составляющая для режимов скорости
_dutyF += (float)deltaInput * kd / _dts; // D составляющая
_prevInput = current; // запомнили текущий
integral += (float)err * ki * _dts; // интегральная сумма
if (cutoff) integral += deltaInput * kp; // +P по скорости изменения для режимов позиции
integral = constrain(integral, -_maxDuty, _maxDuty); // ограничили
_dutyF += integral; // I составляющая
if (cutoff) { // отсечка (для режимов позиции)
if (abs(err) < _stopzone) {integral = 0; _dutyF = 0;}
} else { // для скорости
if (err == 0 && target == 0) integral = 0;
else _dutyF += _sign(err)*_minDuty;
}
_dutyF = constrain(_dutyF, -_maxDuty, _maxDuty); // ограничиваем по 8 или 10 бит
setSpeed(_dutyF); // и поехали
_dutyF = constrain(_dutyF, -_maxDuty, _maxDuty); // ограничиваем по разрешению
if (cutoff && _min != 0 && _max != 0 && (current <= _min || current >= _max)) {
setSpeed(0); // вырубаем, если вышли за диапазон
} else setSpeed(_dutyF); // и поехали
}

void AccelMotor::setRange(long min, long max) {
_min = min;
_max = max;
}
void AccelMotor::setRangeDeg(long min, long max) {
_min = min * _ratio / 360.0;
_max = max * _ratio / 360.0;
}

bool AccelMotor::isBlocked() {
Expand Down Expand Up @@ -113,15 +104,15 @@ long AccelMotor::getCurrent() {
return _currentPos;
}
long AccelMotor::getCurrentDeg() {
return (long)_currentPos * 360 / _ratio;
return (long)_currentPos * 360.0 / _ratio;
}

// ===== current speed =====
int AccelMotor::getSpeed() {
return _curSpeed;
}
int AccelMotor::getSpeedDeg() {
return (long)_curSpeed * 360 / _ratio;
return (long)_curSpeed * 360.0 / _ratio;
}
float AccelMotor::getDuty() {
return _dutyF;
Expand All @@ -133,7 +124,7 @@ void AccelMotor::setTarget(long pos) {
_mode = AUTO;
}
void AccelMotor::setTargetDeg(long pos) {
_targetPos = (long)pos * _ratio / 360;
_targetPos = (long)pos * _ratio / 360.0;
_mode = AUTO;
}
long AccelMotor::getTarget() {
Expand Down
18 changes: 13 additions & 5 deletions AccelMotor/AccelMotor.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
#pragma once
#ifndef AccelMotor_h
#define AccelMotor_h
#include <Arduino.h>
#include <GyverMotor.h>

// v1.1
// v1.2 - совместимость с есп
// v1.3 - небольшие улучшения и фиксы

/*
Библиотека для расширенного управления и стабилизации мотора с энкодером
Expand All @@ -19,6 +21,7 @@
- Все функции работают в градусах и "тиках" энкодера
*/


enum AM_runMode {
ACCEL_POS,
PID_POS,
Expand Down Expand Up @@ -103,12 +106,17 @@ class AccelMotor : public GMotor {
// установить зону остановки мотора для режима стабилизации позиции (по умолч. 8)
void setStopZone(int zone);

// установить пределы шагов/градусов, вне которых мотор будет жёстко отключен для безопасности. Если по нулям, ограничения нет (по умолч.)
void setRange(long min, long max);
void setRangeDeg(long min, long max);

long controlPos = 0; // для отладки
private:
int filter(int newVal);
int _buf[3];
byte _count = 0;
float _middle_f = 0;

long _min = 0, _max = 0;
float _lastSpeed = 0;
void PIDcontrol(long target, long current, bool cutoff);
float integral = 0;
Expand All @@ -120,8 +128,7 @@ class AccelMotor : public GMotor {
float _ratio = 1;
uint32_t _tmr2 = 0;
int _accel = 300;
float _dutyF = 0;
long controlPos = 0;
float _dutyF = 0;
float controlSpeed = 0;
int _stopzone = 8;
long _prevInput = 0;
Expand Down Expand Up @@ -177,4 +184,5 @@ class AccelMotor : public GMotor {
// возвращает -1 при вращении BACKWARD, 1 при FORWARD и 0 при остановке и торможении
int getState();
*/
*/
#endif
103 changes: 103 additions & 0 deletions AccelMotor/examples/motor_demo_pos/motor_demo_pos.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
/*
Пример управления мотором при помощи драйвера полного моста и потенциометра
Для режимов следования к позиции и удержания скорости
*/
#include "AccelMotor.h"
AccelMotor motor(DRIVER2WIRE, 2, 3, HIGH);

// инициализация наследуется от GyverMotor
// варианты инициализации в зависимости от типа драйвера:
// AccelMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, level)
// AccelMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, level)
// AccelMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, level)
/*
DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
RELAY2WIRE - реле в качестве драйвера (два пина направления)
dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
PWM_pin - любой ШИМ пин МК
level - LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
*/

void setup() {
Serial.begin(9600);
// использую мотор JGA25
// редуктор 1:21.3
// энкодер 12 тиков на оборот
motor.setRatio(21.3 * 12);

// период интегрирования (по умолч. 20)
motor.setDt(30); // миллисекунды

// установка максимальной скорости для режима ACCEL_POS
motor.setMaxSpeedDeg(600); // в градусах/сек
//motor.setMaxSpeed(400); // в тиках/сек

// установка ускорения для режима ACCEL_POS
motor.setAccelerationDeg(300); // в градусах/сек/сек
//motor.setAcceleration(300); // в тиках

// минимальный (по модулю) ШИМ сигнал (при котором мотор трогается)
motor.setMinDuty(50);

// коэффициенты ПИД регулятора
motor.kp = 2; // отвечает за резкость регулирования.
// При малых значениях сигнала вообще не будет, при слишком больших – будет трясти

motor.ki = 9; // отвечает за коррекцию ошибки в течение времени
motor.kd = 0.3; // отвечает за компенсацию резких изменений

// установить зону остановки мотора для режима стабилизации позиции в тиках (по умолч. 8)
motor.setStopZone(10);

motor.setRunMode(ACCEL_POS);

// IDLE_RUN - tick() не управляет мотором. Может использоваться для отладки
// ACCEL_POS - tick() работает в режиме плавного следования к целевому углу
// PID_POS - tick() работает в режиме резкого следования к целевому углу
// ACCEL_SPEED - tick() работает в режиме плавного поддержания скорости (с заданным ускорением)
// PID_SPEED - tick() работает в режиме поддержания скорости по ПИД регулятору
}

void loop() {
// потенциометр на А0
// преобразуем значение в -255.. 255
static float val;
val += (255 - analogRead(0) / 2 - val) * 0.3; // фильтор

// для режима PID_POS/ACCEL_POS
motor.setTargetDeg(val * 2); // задаём новый целевой угол в градусах

// обязательная функция. Делает все вычисления
// принимает текущее значение с энкодера или потенциометра
motor.tick(encTick(4));

static uint32_t tmr = 0;
if (millis() - tmr > 100) { // таймер на 100мс для графиков
tmr += 100;

// отладка позиции (открой плоттер)
Serial.print(motor.getTarget());
Serial.print(',');
Serial.print(motor.getDuty());
Serial.print(',');
Serial.print(motor.controlPos);
Serial.print(',');
Serial.println(motor.getCurrent());
}
}

// читаем энкодер вручную, через digitalRead()
long encTick(byte pin) {
static bool lastState;
static long encCounter = 0;
bool curState = digitalRead(pin); // опрос
if (lastState != curState) { // словили изменение
lastState = curState;
if (curState) { // по фронту
encCounter += motor.getState(); // запомнили поворот
}
}
return encCounter;
}
101 changes: 101 additions & 0 deletions AccelMotor/examples/motor_demo_speed/motor_demo_speed.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
/*
Пример управления мотором при помощи драйвера полного моста и потенциометра
Для режимов следования к позиции и удержания скорости
*/
#include "AccelMotor.h"
AccelMotor motor(DRIVER2WIRE, 2, 3, HIGH);

// инициализация наследуется от GyverMotor
// варианты инициализации в зависимости от типа драйвера:
// AccelMotor motor(DRIVER2WIRE, dig_pin, PWM_pin, level)
// AccelMotor motor(DRIVER3WIRE, dig_pin_A, dig_pin_B, PWM_pin, level)
// AccelMotor motor(RELAY2WIRE, dig_pin_A, dig_pin_B, level)
/*
DRIVER2WIRE - двухпроводной драйвер (направление + ШИМ)
DRIVER3WIRE - трёхпроводной драйвер (два пина направления + ШИМ)
RELAY2WIRE - реле в качестве драйвера (два пина направления)
dig_pin, dig_pin_A, dig_pin_B - любой цифровой пин МК
PWM_pin - любой ШИМ пин МК
level - LOW / HIGH - уровень драйвера. Если при увеличении скорости мотор наоборот тормозит - смени уровень
*/

void setup() {
Serial.begin(9600);
// использую мотор JGA25
// редуктор 1:21.3
// энкодер 12 тиков на оборот
motor.setRatio(21.3 * 12);

// период интегрирования (по умолч. 20)
motor.setDt(30); // миллисекунды

// установка максимальной скорости для режима ACCEL_POS
motor.setMaxSpeedDeg(600); // в градусах/сек
//motor.setMaxSpeed(400); // в тиках/сек

// установка ускорения для режима ACCEL_POS
motor.setAccelerationDeg(300); // в градусах/сек/сек
//motor.setAcceleration(300); // в тиках

// минимальный (по модулю) ШИМ сигнал (при котором мотор трогается)
motor.setMinDuty(50);

// коэффициенты ПИД регулятора
motor.kp = 2; // отвечает за резкость регулирования.
// При малых значениях сигнала вообще не будет, при слишком больших – будет трясти

motor.ki = 0.2; // отвечает за коррекцию ошибки в течение времени
motor.kd = 0.1; // отвечает за компенсацию резких изменений

// установить зону остановки мотора для режима стабилизации позиции в тиках (по умолч. 8)
motor.setStopZone(10);

motor.setRunMode(PID_SPEED);

// IDLE_RUN - tick() не управляет мотором. Может использоваться для отладки
// ACCEL_POS - tick() работает в режиме плавного следования к целевому углу
// PID_POS - tick() работает в режиме резкого следования к целевому углу
// ACCEL_SPEED - tick() работает в режиме плавного поддержания скорости (с заданным ускорением)
// PID_SPEED - tick() работает в режиме поддержания скорости по ПИД регулятору
}

void loop() {
// потенциометр на А0
// преобразуем значение в -255.. 255
static float val;
val += (255 - analogRead(0) / 2 - val) * 0.3; // фильтор

// для режима PID_SPEED/ACCEL_SPEED
motor.setTargetSpeedDeg(val * 4); // задаём целевую скорость в градусах/сек

// обязательная функция. Делает все вычисления
// принимает текущее значение с энкодера или потенциометра
motor.tick(encTick(4));

static uint32_t tmr = 0;
if (millis() - tmr > 100) { // таймер на 100мс для графиков
tmr += 100;

// отладка скорости (открой плоттер)
Serial.print(motor.getTargetSpeedDeg());
Serial.print(',');
Serial.print(motor.getDuty());
Serial.print(',');
Serial.println(motor.getSpeedDeg());
}
}

// читаем энкодер вручную, через digitalRead()
long encTick(byte pin) {
static bool lastState;
static long encCounter = 0;
bool curState = digitalRead(pin); // опрос
if (lastState != curState) { // словили изменение
lastState = curState;
if (curState) { // по фронту
encCounter += motor.getState(); // запомнили поворот
}
}
return encCounter;
}
2 changes: 2 additions & 0 deletions AccelMotor/keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ getDuty KEYWORD2
setRunMode KEYWORD2
setStopZone KEYWORD2
isBlocked KEYWORD2
setRange KEYWORD2
setRangeDeg KEYWORD2
kp KEYWORD2
ki KEYWORD2
kd KEYWORD2
Expand Down
2 changes: 1 addition & 1 deletion AccelMotor/library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=AccelMotor
version=0.0
version=1.3
author=AlexGyver <alex@alexgyver.ru>
maintainer=AlexGyver <alex@alexgyver.ru>
sentence=Library for motor smooth control
Expand Down
4 changes: 3 additions & 1 deletion Gyver433/Gyver433.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#pragma once
#ifndef Gyver433_h
#define Gyver433_h
/*
Суперлёгкая библиотека для радиомодулей 433 МГц
- Не использует прерывания и таймеры (кроме нулевого, читает micros())
Expand Down Expand Up @@ -232,3 +233,4 @@ byte G433_crc(byte *buffer, byte size) {
for (byte i = 0; i < size; i++) G433_crc_byte(crc, buffer[i]);
return crc;
}
#endif
Loading

0 comments on commit 92a5ad7

Please sign in to comment.