Skip to content

Commit

Permalink
add
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexGyver committed May 25, 2021
1 parent c96180d commit 9a11eff
Show file tree
Hide file tree
Showing 40 changed files with 2,149 additions and 0 deletions.
134 changes: 134 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
![License: MIT](https://img.shields.io/badge/License-MIT-green.svg)
![author](https://img.shields.io/badge/author-AlexGyver-informational.svg)
# GyverPID
GyverPID - библиотека PID регулятора для Arduino
- Время одного расчёта около 70 мкс
- Режим работы по величине или по её изменению (для интегрирующих процессов)
- Возвращает результат по встроенному таймеру или в ручном режиме
- Встроенные калибровщики коэффициентов
- Режим работы по ошибке и по ошибке измерения
- Встроенные оптимизаторы интегральной суммы

### Совместимость
Совместима со всеми Arduino платформами (используются Arduino-функции)

### Документация
К библиотеке есть [расширенная документация](https://alexgyver.ru/GyverPID/)

## Содержание
- [Установка](#install)
- [Инициализация](#init)
- [Использование](#usage)
- [Пример](#example)
- [Версии](#versions)
- [Баги и обратная связь](#feedback)

<a id="install"></a>
## Установка
- Библиотеку можно найти по названию **GyverPID** и установить через менеджер библиотек в:
- Arduino IDE
- Arduino IDE v2
- PlatformIO
- [Скачать библиотеку](https://github.com/GyverLibs/GyverPID/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)

<a id="init"></a>
## Инициализация
```cpp
// Можно инициализировать объект тремя способами:
GyverPID regulator; // инициализировать без настроек (всё по нулям, dt 100 мс)
GyverPID regulator(kp, ki, kd); // инициализировать с коэффициентами. dt будет стандартно 100 мс
GyverPID regulator(kp, ki, kd, dt); // инициализировать с коэффициентами и dt (в миллисекундах)
```
<a id="usage"></a>
## Использование
Смотри [документацию](https://alexgyver.ru/GyverPID/)
```cpp
datatype setpoint = 0; // заданная величина, которую должен поддерживать регулятор
datatype input = 0; // сигнал с датчика (например температура, которую мы регулируем)
datatype output = 0; // выход с регулятора на управляющее устройство (например величина ШИМ или угол поворота серво)
datatype getResult(); // возвращает новое значение при вызове (если используем свой таймер с периодом dt!)
datatype getResultTimer(); // возвращает новое значение не ранее, чем через dt миллисекунд (встроенный таймер с периодом dt)
void setDirection(boolean direction); // направление регулирования: NORMAL (0) или REVERSE (1)
void setMode(boolean mode); // режим: работа по входной ошибке ON_ERROR (0) или по изменению ON_RATE (1)
void setLimits(int min_output, int max_output); // лимит выходной величины (например для ШИМ ставим 0-255)
void setDt(int16_t new_dt); // установка времени дискретизации (для getResultTimer)
float Kp = 0.0;
float Ki = 0.0;
float Kd = 0.0;
```

<a id="example"></a>
## Пример
Остальные примеры смотри в **examples**!
```cpp
/*
Пример работы ПИД регулятора в автоматическом режиме по встроенному таймеру
Давайте представим, что на 3 пине у нас спираль нагрева, подключенная через мосфет,
управляем ШИМ сигналом
И есть какой то абстрактный датчик температуры, на который влияет спираль
*/

// перед подключением библиотеки можно добавить настройки:
// сделает часть вычислений целочисленными, что чуть (совсем чуть!) ускорит код
// #define PID_INTEGER

// режим, при котором интегральная составляющая суммируется только в пределах указанного количества значений
// #define PID_INTEGRAL_WINDOW 50
#include "GyverPID.h"

GyverPID regulator(0.1, 0.05, 0.01, 10); // коэф. П, коэф. И, коэф. Д, период дискретизации dt (мс)
// или так:
// GyverPID regulator(0.1, 0.05, 0.01); // можно П, И, Д, без dt, dt будет по умолч. 100 мс

void setup() {
regulator.setDirection(NORMAL); // направление регулирования (NORMAL/REVERSE). ПО УМОЛЧАНИЮ СТОИТ NORMAL
regulator.setLimits(0, 255); // пределы (ставим для 8 битного ШИМ). ПО УМОЛЧАНИЮ СТОЯТ 0 И 255
regulator.setpoint = 50; // сообщаем регулятору температуру, которую он должен поддерживать

// в процессе работы можно менять коэффициенты
regulator.Kp = 5.2;
regulator.Ki += 0.5;
regulator.Kd = 0;
}

void loop() {
int temp; // читаем с датчика температуру
regulator.input = temp; // сообщаем регулятору текущую температуру

// getResultTimer возвращает значение для управляющего устройства
// (после вызова можно получать это значение как regulator.output)
// обновление происходит по встроенному таймеру на millis()
analogWrite(3, regulator.getResultTimer()); // отправляем на мосфет

// .getResultTimer() по сути возвращает regulator.output
}
```
<a id="versions"></a>
## Версии
- v1.1 - убраны дефайны
- v1.2 - возвращены дефайны
- v1.3 - вычисления ускорены, библиотека облегчена
- v2.0 - логика работы чуть переосмыслена, код улучшен, упрощён и облегчён
- v2.1 - integral вынесен в public
- v2.2 - оптимизация вычислений
- v2.3 - добавлен режим PID_INTEGRAL_WINDOW
- v2.4 - реализация внесена в класс
- v3.0
- Добавлен режим оптимизации интегральной составляющей (см. доку)
- Добавлены автоматические калибровщики коэффициентов (см. примеры и доку)
- v3.1 - исправлен режиме ON_RATE, добавлено автоограничение инт. суммы
- v3.2 - чуть оптимизации, добавлена getResultNow
- v3.3 - в тюнерах можно передать другой обработчик класса Stream для отладки
<a id="feedback"></a>
## Баги и обратная связь
При нахождении багов создавайте **Issue**, а лучше сразу пишите на почту [alex@alexgyver.ru](mailto:alex@alexgyver.ru)
Библиотека открыта для доработки и ваших **Pull Request**'ов!
Binary file added docs/tuner cohen-coon plot.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/tuner cohen-coon text.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/tuner relay debug plot.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/tuner relay debug text.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
64 changes: 64 additions & 0 deletions examples/autotune/pcfan-pwm/PIDtest/PIDtest.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// тест коэффициентов из тюнера. Система: 4 пин вентилятор
#define PWM_PIN 3
#define TACH_PIN 2

#include "Tacho.h"
Tacho tacho;

#include "GyverPID.h"
// analysis: 100% PI p: 0.61 PI i: 0.43 PID p: 0.92 PID i: 1.07 PID d: 0.20
// analysis: 100% PI p: 0.79 PI i: 0.89 PID p: 1.04 PID i: 0.53 PID d: 0.36

GyverPID pid(0.92, 1.07, 0.20);
int period = 30;

void setup() {
Serial.begin(9600);
Serial.setTimeout(50);

pinMode(PWM_PIN, OUTPUT);

// пин тахометра вентилятора подтягиваем к VCC
pinMode(TACH_PIN, INPUT_PULLUP);

// настраиваем прерывание
attachInterrupt(0, isr, FALLING);

pid.setpoint = 200;
pid.setDt(period);
}

// обработчик прерывания
void isr() {
tacho.tick(); // сообщаем библиотеке об этом
}

void loop() {
static uint32_t tmr;
if (millis() - tmr >= period) {
tmr = millis();
pid.input = tacho.getRPM(); // даём регулятору обороты
pid.getResult(); // считаем
analogWrite(PWM_PIN, pid.output); // отправляем на ШИМ

Serial.print(pid.input); Serial.print(' ');
Serial.print(pid.output); Serial.print(' ');
Serial.print(pid.integral); Serial.print(' ');
Serial.println(pid.setpoint);
}
parsing();
}

// управление через плоттер
void parsing() {
if (Serial.available() > 1) {
char incoming = Serial.read();
float value = Serial.parseFloat();
switch (incoming) {
case 'p': pid.Kp = value; break;
case 'i': pid.Ki = value; break;
case 'd': pid.Kd = value; break;
case 's': pid.setpoint = value; break;
}
}
}
50 changes: 50 additions & 0 deletions examples/autotune/pcfan-pwm/PIDtest/Tacho.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#pragma once

// класс тахометра
// встроенный медианный фильтр
// вызывай tick в прерывании по фронту

#define _TACHO_TICKS_AMOUNT 5 // количество тиков для усреднения
#define _TACHO_TIMEOUT 1000000 // таймаут прерываний (мкс), после которого считаем что вращение прекратилось

class Tacho {
public:
void tick() {
ticks++;
if (ticks == _TACHO_TICKS_AMOUNT) {
ticks = 0;
tachoTime = micros() - tachoTimer;
tachoTimer += tachoTime; //tachoTimer = micros();
ready = true;
}
}

int getRPM() {
if (ready) { // если готовы новые данные
ready = false;
rpm = median3(6ul * _TACHO_TICKS_AMOUNT * 1000000 / tachoTime);
}
if (micros() - tachoTimer > _TACHO_TIMEOUT) rpm = 0;
return rpm;
}

private:
// быстрая медиана
int median3(int value) {
buf[counter] = value;
if (++counter > 2) counter = 0;
if ((buf[0] <= buf[1]) && (buf[0] <= buf[2])) return (buf[1] <= buf[2]) ? buf[1] : buf[2];
else {
if ((buf[1] <= buf[0]) && (buf[1] <= buf[2])) return (buf[0] <= buf[2]) ? buf[0] : buf[2];
else return (buf[0] <= buf[1]) ? buf[0] : buf[1];
}
}

volatile long tachoTime = 0;
volatile uint32_t tachoTimer = 0;
volatile byte ticks = 0;
volatile bool ready;
int buf[3];
byte counter = 0;
int rpm = 0;
};
50 changes: 50 additions & 0 deletions examples/autotune/pcfan-pwm/pid_autotune/Tacho.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#pragma once

// класс тахометра
// встроенный медианный фильтр
// вызывай tick в прерывании по фронту

#define _TACHO_TICKS_AMOUNT 5 // количество тиков для усреднения
#define _TACHO_TIMEOUT 1000000 // таймаут прерываний (мкс), после которого считаем что вращение прекратилось

class Tacho {
public:
void tick() {
ticks++;
if (ticks == _TACHO_TICKS_AMOUNT) {
ticks = 0;
tachoTime = micros() - tachoTimer;
tachoTimer += tachoTime; //tachoTimer = micros();
ready = true;
}
}

int getRPM() {
if (ready) { // если готовы новые данные
ready = false;
rpm = median3(6ul * _TACHO_TICKS_AMOUNT * 1000000 / tachoTime);
}
if (micros() - tachoTimer > _TACHO_TIMEOUT) rpm = 0;
return rpm;
}

private:
// быстрая медиана
int median3(int value) {
buf[counter] = value;
if (++counter > 2) counter = 0;
if ((buf[0] <= buf[1]) && (buf[0] <= buf[2])) return (buf[1] <= buf[2]) ? buf[1] : buf[2];
else {
if ((buf[1] <= buf[0]) && (buf[1] <= buf[2])) return (buf[0] <= buf[2]) ? buf[0] : buf[2];
else return (buf[0] <= buf[1]) ? buf[0] : buf[1];
}
}

volatile long tachoTime = 0;
volatile uint32_t tachoTimer = 0;
volatile byte ticks = 0;
volatile bool ready;
int buf[3];
byte counter = 0;
int rpm = 0;
};
41 changes: 41 additions & 0 deletions examples/autotune/pcfan-pwm/pid_autotune/pid_autotune.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// пример тюнера. Система: 4 пин вентилятор
#define PWM_PIN 3
#define TACH_PIN 2

#include "PIDtuner.h"
PIDtuner tuner;

#include "Tacho.h"
Tacho tacho;

void setup() {
Serial.begin(9600);
pinMode(PWM_PIN, OUTPUT);

// пин тахометра вентилятора подтягиваем к VCC
pinMode(TACH_PIN, INPUT_PULLUP);

// настраиваем прерывание
attachInterrupt(0, isr, FALLING);

// направление, сигнал, ступенька, период стабилизации, точность стабилизации, продолж. импульса, период итерации
tuner.setParameters(NORMAL, 130, 40, 2000, 1, 2000, 30);
}

// обработчик прерывания
void isr() {
tacho.tick(); // сообщаем библиотеке об этом
}


void loop() {
tuner.setInput(tacho.getRPM()); // даём тюнеру текущие обороты
tuner.compute(); // считаем
analogWrite(PWM_PIN, tuner.getOutput()); // отправляем как ШИМ

// выводит в порт текстовые отладочные данные, включая коэффициенты
tuner.debugText();

// выводит в порт данные для построения графиков, без коэффициентов
//tuner.debugPlot();
}
7 changes: 7 additions & 0 deletions examples/autotune/pcfan-pwm/внимание!.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
Класс тахометр здесь работает не очень корректно (значения в 10 раз меньше реальных),
но регулятор в примерах с тестами настроен именно на такие значения.
Актуальная исправленная версия библиотеки тахометра лежит тут https://github.com/AlexGyver/GyverLibs/blob/master/minimLibs/tachometer/Tacho.h
в своих целях используйте именно её

Также для стабильной работы вентилятора рекомендуется внешняя подтяжка 10 кОм к VCC,
а ШИМ пин подключать через резистор ~220 Ом. Но скорее всего будет стабильно и без него.
40 changes: 40 additions & 0 deletions examples/autotune/simulation/PIDtest/PIDtest.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// тест коэффициентов из тюнера на синтетическом нагревательном процессе

#include "GyverPID.h"
GyverPID pid(0.7, 0.5, 0.2);
int period = 50;

void setup() {
Serial.begin(9600);
Serial.setTimeout(50);
pid.setpoint = 40;
pid.setDt(period);
}

void loop() {
static uint32_t tmr;
if (millis() - tmr >= period) {
tmr = millis();
pid.input = process(pid.output);
pid.getResult();

Serial.print(pid.input); Serial.print(' ');
Serial.print(pid.output); Serial.print(' ');
Serial.print(pid.integral); Serial.print(' ');
Serial.println(pid.setpoint);
}
parsing();
}

void parsing() {
if (Serial.available() > 1) {
char incoming = Serial.read();
float value = Serial.parseFloat();
switch (incoming) {
case 'p': pid.Kp = value; break;
case 'i': pid.Ki = value; break;
case 'd': pid.Kd = value; break;
case 's': pid.setpoint = value; break;
}
}
}
Loading

0 comments on commit 9a11eff

Please sign in to comment.