Commit 7e6ca871 authored by Oleg Nikulin's avatar Oleg Nikulin

PID регулятор оборотов вентилятора

parent bf58d042
......@@ -6,29 +6,33 @@
#define FAN_COUNT 6 //Количество вентиляторов
#define BAUDRATE 19200 //Скорость serial порта
#define BEEP_INTERVAL 1000 //Частота пищания во время потери связи или перегрева
#define BEEP_STRENGTH 100 //Уровень шима для пищалки. (При 255 не работает)
#define BLINK_INTERVAL 200 //Частота мигания светодиода во время ожидания ответа от пк
#define CHECK_TEMP_DELAY 1000 //Задержка перед очередным получением температуры от пк
#define GET_TEMP_TIMEOUT 500 //Если в течение этого времени температура не была прислана, считается что пк не отвечает
#define RPM_CHECK_INTERVAL 1000 //Частота подсчета rpm и обнуления tachRevs
#define DEFAULT_PWM_DUTY_CYCLE 254 //Скважность ШИМ поумолчанию (до подулючения к пк)
#define CHECK_TEMP_DELAY 200 //Интервал получения температуры от пк (мс)
#define GET_TEMP_TIMEOUT 1000 //Если в течение этого времени температура не была прислана, считается что пк не отвечает (мс)
#define RPM_CHECK_INTERVAL 200 //Интервал подсчета rpm и обнуления tachRevs (мс)
#define RPM_VALUES_COUNT 5 //Количество значений RPM, которые записываются и усредняются (скользящее среднее)
#define MAX_PWM_DUTY_CYCLE 254 //Максимальная скважность ШИМ
#define DEFAULT_PWM_DUTY_CYCLE 254 //Скважность ШИМ по умолчанию (до подулючения к пк)
#define BEEP_INTERVAL 1000 //Интервал пищания во время потери связи или перегрева (мс)
#define BEEP_STRENGTH 255 //Уровень ШИМ для пищалки. (При 255 не работает, нужно чтобы был именно ШИМ)
#define BLINK_INTERVAL 200 //Интервал мигания светодиода во время ожидания ответа от пк (мс)
#define SOUND_PIN 10
#define LED_PIN 13
#define SOUND_PIN 10 //Номер пина пищалки
#define LED_PIN 13 //Номер пина светодиода
int pwmPins[3] = {3, 5, 6}; //Номера пинов ШИМ
bool pwmState = 0; //Состояние ШИМ
volatile bool pwmState = 0; //Состояние ШИМ
volatile bool pwm_on = 1; // ==1, если ШИМ включен
int tachPins[FAN_COUNT] = {14, 15, 16, 17, 18, 19}; //Номера пинов для считывания оборотов
uint16_t tachRevs[FAN_COUNT] = {}; //Обороты (просто сколько насчитано оборотов, а не rpm)
uint16_t tachRpm[FAN_COUNT] = {}; //rpm
bool tachStates[FAN_COUNT] = {}; //Состояния (оборот считывается только если состояние == 0, и считывается 0)
volatile uint16_t tachRevs[FAN_COUNT] = {}; //Обороты (просто сколько насчитано оборотов, а не rpm)
uint16_t tachRpm[FAN_COUNT][RPM_VALUES_COUNT] = {}; //rpm
volatile bool tachStates[FAN_COUNT] = {}; //Состояния (оборот считывается только если состояние == 0, и считывается 0)
//Это пока не используется:
struct fan { //Данные о вентиляторе
/*
struct fan { //Данные о вентиляторе
int tachPin; //Номер пина тахометра
bool tachState; //Состояние тахометра
bool tachType; //Тип датчика. 0 = униполярный, 1 = биполярный
......@@ -36,20 +40,29 @@ struct fan { //Данные о вентиляторе
uint16_t rpm; //Обороты в минуту
uint32_t lastSignalStart; //Время начала последнего сигнала тахометра
uint32_t lastSignalEnd; //Время окончания последнего сигнала тахометра
};
};
struct controll { //Данные о контроллерах вентилятора
struct control { //Данные о контроллерах вентилятора
int pwmPin; //Номер пина ШИМ
bool pwmState; //Состояние пина ШИМ
};
};
*/
int temp; //Температура, полученная от пк
int target_rpm = 0;
uint32_t last_beep_time = 0;
uint32_t last_check_time = 0;
uint32_t lastRpmCheck = 0;
uint32_t lastRevTime = 0;
float p = 0;
float i = 0;
float d = 0;
float k_p = 0.3;
float k_i = 0.0004;
float k_d = 160;
......@@ -92,15 +105,21 @@ void wait_for_connection(bool beep) { //функция, которая мига
void tempFromPc()// получаем температуру от пк
{
String rpm_string = "send_rpm_";
for (int i = 0; i < FAN_COUNT; i++) {
for (int fan = 0; fan < FAN_COUNT; fan++) {
uint32_t avg_rpm = 0;
for (int val = 0; val < RPM_VALUES_COUNT; val++) {
avg_rpm += tachRpm[fan][val];
}
avg_rpm /= RPM_VALUES_COUNT;
rpm_string += String(tachRpm[i]);
if (i < 5) {
rpm_string += String(avg_rpm);
if (fan < 5) {
rpm_string += "_";
}
}
Serial.println("req_temperature_" + rpm_string); //запрос к пк
Serial.println("req_temperature_" + rpm_string + "_debug_" + String(OCR2A)); //запрос к пк
unsigned long query_time = millis();
while (Serial.available() == 0) { //ждем пока ответит
if (millis() >= query_time + GET_TEMP_TIMEOUT) { //если слишком долго не отвечает
......@@ -122,49 +141,114 @@ void tempFromPc()// получаем температуру от пк
void autocontrol()//Автоконтроль температуры
{
tempFromPc();//получаем температуру от пк
int pwmDutyCycle = 0;
/*
if (temp < 20) { //<20 rpm = 600-630
target_rpm = 650;
//pwmDutyCycle = 50;
}
else if (temp < 40) { //20-39 rpm = 1080-1110
target_rpm = 1000;
//pwmDutyCycle = 100;
}
else if (temp < 60) { //40-59 rpm = 1380-1410
target_rpm = 1250;
//pwmDutyCycle = 150;
}
else if (temp < 80) { //60-79 rpm = 1620-1650
target_rpm = 1500;
//pwmDutyCycle = 200;
}
else { //>=80 rpm = 1800-1830
target_rpm = 1700;
//pwmDutyCycle = 254;
}
*/
target_rpm = temp;
}
if (temp < 20) { //<20 rpm = 600-630
pwmDutyCycle = 50;
void rpm_control() {
for (int fan = 0; fan < FAN_COUNT; fan++) {
for (int val = 0; val < RPM_VALUES_COUNT - 1; val++) {
tachRpm[fan][val] = tachRpm[fan][val + 1];
}
tachRpm[fan][RPM_VALUES_COUNT - 1] = (tachRevs[fan] * (60000 / uint32_t(millis() - lastRpmCheck))) / 2;
tachRevs[fan] = 0;
}
else if (temp < 40) { //20-39 rpm = 1080-1110
pwmDutyCycle = 100;
uint32_t avg_rpm = 0;
const int fan = 0;
for (int val = 0; val < RPM_VALUES_COUNT; val++) {
avg_rpm += tachRpm[fan][val];
}
else if (temp < 60) { //40-59 rpm = 1380-1410
pwmDutyCycle = 150;
avg_rpm /= RPM_VALUES_COUNT;
float pwmDutyCycle = 0;
uint8_t byte_pwmDutyCycle = 0;
d = (target_rpm - int(avg_rpm) - p) / float(millis() - lastRpmCheck);
p = target_rpm - int(avg_rpm);
i = i + p * (millis() - lastRpmCheck);
pwmDutyCycle = round(p * k_p + i * k_i + d * k_d);
if (pwmDutyCycle <= 1) {
byte_pwmDutyCycle = 1;
}
else if (temp < 80) { //60-79 rpm = 1620-1650
pwmDutyCycle = 200;
else if (pwmDutyCycle >= MAX_PWM_DUTY_CYCLE) {
byte_pwmDutyCycle = MAX_PWM_DUTY_CYCLE;
}
else { //>=80 rpm = 1800-1830
pwmDutyCycle = MAX_PWM_DUTY_CYCLE;
else {
byte_pwmDutyCycle = pwmDutyCycle;
}
if (pwmDutyCycle == 0) {
TIMSK2 &= (0 << OCIE2A); //выкл. вызов прерывания
pwmState = 0;
for (int i = 0; i < 3; i++) {
digitalWrite(pwmPins[i], 0);
if (byte_pwmDutyCycle == 0) {
if (pwm_on == 1) {
pwm_on = 0; //выкл ШИМ
for (int i = 0; i < 3; i++) {//выкл пины ШИМ
digitalWrite(pwmPins[i], 0);
}
}
}
else {
OCR2A = pwmDutyCycle; //установка скважности
if (pwm_on == 0) {
pwm_on = 1; //вкл ШИМ
}
OCR2A = byte_pwmDutyCycle; //установка скважности
}
//Почему-то иногда может заглючить: скважность стоит 254, pwm_on равно 1, но вентилятор не крутится (но пищит). Похоже каким-то образом меняется pwmState, когда не надо
//Serial.println("debug_" + String(byte_pwmDutyCycle));
lastRpmCheck = millis();
}
ISR(TIMER2_COMPA_vect) { //Эта функия вызывается при прерывании по таймеру 2
pwmState = !pwmState;
if (pwmState == 1) {
pwmState = 0;
}
else {
pwmState = 1;
}
for (int i = 0; i < 3; i++) {//управление пинами ШИМ
digitalWrite(pwmPins[i], pwmState);
}
if (pwmState == 1) { //Если питание включилось, то проверяем состояния тахометров
for (int i = 0; i < FAN_COUNT; i++) {
//Пины тахометров подтянуты к 5в. Если digitalRead == 0, то считается, что тахометр активен, поэтому tachState[i] == 1
if (digitalRead(tachPins[i]) == 0 && tachStates[i] == 0) { //сигнал тахометра появился
tachStates[i] = 1;
//digitalWrite(13, 1);
......@@ -189,18 +273,18 @@ ISR(TIMER2_COMPA_vect) { //Эта функия вызывается при пр
void setup() {
pinMode(LED_PIN, OUTPUT);
pinMode(SOUND_PIN, OUTPUT);
for (int i = 0; i < 3; i++) {
pinMode(pwmPins[i], OUTPUT);
}
for (int i = 0; i < FAN_COUNT; i++) {
pinMode(tachPins[i], INPUT_PULLUP);
pinMode(tachPins[i], INPUT_PULLUP);
}
TCCR2A |= (1 << WGM20); //запуск таймера
OCR2A = 1; //скважность
OCR2A = DEFAULT_PWM_DUTY_CYCLE; //скважность
TIMSK2 |= (1 << OCIE2A); //вкл. вызов прерывания
......@@ -218,8 +302,8 @@ void loop() {
last_check_time = millis();
autocontrol(); //Получаем температуру от ПК, устанавливаем соотв. скорость вращения
if (temp >= 80) { //Если перегрев, включается пищалка
/*
if (temp >= 80) { //Если перегрев, включается пищалка
if (millis() >= last_beep_time + BEEP_INTERVAL * 2) {
analogWrite(SOUND_PIN, BEEP_STRENGTH);
last_beep_time = millis();
......@@ -227,18 +311,14 @@ void loop() {
else if (millis() >= last_beep_time + BEEP_INTERVAL) {
analogWrite(SOUND_PIN, 0);
}
}
else {
}
else {
analogWrite(SOUND_PIN, 0); //Чтобы постоянно не пищал, если температура станет < 80 в то время, как пищалка включена
}
}
*/
}
if (uint32_t(millis() - lastRpmCheck) >= RPM_CHECK_INTERVAL) { //подсчет rpm
for (int i = 0; i < FAN_COUNT; i++) {
tachRpm[i] = (tachRevs[i] * (60000 / uint32_t(millis() - lastRpmCheck))) / 2;
tachRevs[i] = 0;
}
lastRpmCheck = millis();
if (uint32_t(millis() - lastRpmCheck) >= RPM_CHECK_INTERVAL) {
rpm_control();
}
}
......@@ -169,6 +169,13 @@ while True:
print('Fan RPMs: ' + rpm_str)
if args.manual: print('Enter the temperature value: ')
if 'debug' in incoming_line:
debug_pos = incoming_line.find('debug')
debug_str = incoming_line[debug_pos + 6:]
if args.manual: print()
print('debug: ' + debug_str)
if args.manual: print('Enter the temperature value: ')
except OSError:
if connected:
print('Serial divice was disconnected. Trying to reconnect...')
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment