Nebelmaschine/Firmware/test3_tiny2313.c

312 lines
7.1 KiB
C

//https://homepages.uni-regensburg.de/~erc24492/PID-Regler/AVR221/IAR/doxygen/main_8c-source.html
#include <avr/interrupt.h>
#include <avr/io.h>
#include <stdio.h>
#include "pid.h"
#define F_CPU 8000000UL
#define BAUD 250000UL
#define F_TIMER 80L // Timer1 ISR-Frequenz != 1Hz
#define T1_PRESCALER 1024 // Hardware-Vorteiler für Timer 1,
// muss mit der Konfiguratiom übereinstimmen!
#define OCRx_RELOAD ((F_CPU / (T1_PRESCALER * F_TIMER)) -1) // Periodendauer pro Interrupt
#define UBRR_VAL ((F_CPU+BAUD*8)/(BAUD*16)-1)
#define BAUD_REAL (F_CPU/(16*(UBRR_VAL+1)))
#define BAUD_ERROR ((BAUD_REAL*1000)/BAUD)
#if ((BAUD_ERROR<990) || (BAUD_ERROR>1010))
#error
#endif
#define HEATER_PIN_OUT DDRB |= (1<<PB4);
#define PUMP_PIN_OUT DDRB |= (1<<PB3);
#define HEATER_ON PORTB |= (1<<PB4);
#define HEATER_OFF PORTB &= ~(1<<PB4);
#define PUMP_ON PORTB |= (1<<PB3);
#define PUMP_OFF PORTB &= ~(1<<PB3);
//MISO = PB6 DO
//MOSI = PB5 DI
//CS = PB1
//SCK = PB7
#define CS_DIS PORTB |= (1<<PB1);
#define CS_EN PORTB &= ~(1<<PB1);
#define DMX_BAUD 250000
#define DMX_LOST_TIMEOUT 8000
volatile unsigned int dmx_lost = DMX_LOST_TIMEOUT;
volatile unsigned int dmx_adresse = 1;
volatile unsigned char dmx_buffer[2];
//volatile unsigned char led_kanal[3];
volatile unsigned long temperature;
//4500 ca 285°C //OFF
//4400 ca 278°C
//4300 ca 272°C
//4250 ca 270°C
//4200 ca 262°C
// ca 250°C //ON
//3800 ca 238°C
//3500 ca 220°C
//3200 ca 200°C
//2800 ca 175°C
//2500 ca 156°C
//2200 ca 138°C
//1800 ca 115°C
//1400 ca 100°C
//1200 ca 80°C
//570 ca 50°C
//340 ca 25°C
//KR bei 125V = 520 -> 130 bei 230V
//P_C ca 90s
//PWM bei 3670 (275°C)
//heizen 32000 bei DMX-Wert= 32
struct PID_DATA pidData;
int16_t p_factor = 85; //85
int16_t i_factor = 0; //1
int16_t d_factor = 40; //11
int16_t processValue = 1024; //Ist-Temp
int16_t setPoint = 4220; //Soll-Temp (275°C) 4220
int16_t Factor = (32767/80);
volatile int16_t PWM = 0; //16Bit PWM
volatile uint8_t PUMP = 0; //8Bit PWM
volatile int8_t T = 0;
void Fehler() {
cli(); //Interrupts aus
HEATER_OFF; //Heizung aus
PUMP_OFF; //Pumpe aus
while (1) {
//Hält Maschine bei Fehler an
}
}
long spi()
{
//Max31855 einlesen
unsigned char y = 0;
unsigned char x = 0;
long wert;
CS_EN; //Enable CS
for(unsigned long tmpa = 0;tmpa<5;tmpa++)asm("nop"); //ca 100ns warten
//Byte 1
USIDR = 0x0;
USISR = (1<<USIOIF);
do {
USICR = (1<<USIWM0)|(1<<USICS1)|(1<<USICLK)|(1<<USITC);
} while ((USISR & (1<<USIOIF)) == 0);
x = (unsigned int)USIDR;
// Byte2
USIDR = 0x0;
USISR = (1<<USIOIF);
do {
USICR = (1<<USIWM0)|(1<<USICS1)|(1<<USICLK)|(1<<USITC);
} while ((USISR & (1<<USIOIF)) == 0);
y = (unsigned int)USIDR;
// Byte 3
USIDR = 0x0;
USISR = (1<<USIOIF);
do {
USICR = (1<<USIWM0)|(1<<USICS1)|(1<<USICLK)|(1<<USITC);
} while ((USISR & (1<<USIOIF)) == 0);
//Byte 4
USIDR = 0x0;
USISR = (1<<USIOIF);
do {
USICR = (1<<USIWM0)|(1<<USICS1)|(1<<USICLK)|(1<<USITC);
} while ((USISR & (1<<USIOIF)) == 0);
CS_DIS; //Disable CS
//Prüfen ob Sensor angeschlossen ist
if (y & 0x01) {Fehler();}
wert = (unsigned long) (((long)x << 8) | (long)y);
return wert;
}
void enable_spi(unsigned char speed)
{
if (speed) {
PORTB |= (1<<PB6)|(1<<PB1); // pull-up i.e. disabled
DDRB |= (1<<PB7)|(1<<PB6)|(1<<PB1);
USICR = (1<<USIWM0)|(1<<USICS1)|(1<<USICLK);
DDRB &= ~(1<<PB5); //Input: PB6=DI (MOSI)
PORTB |= (1<<PB5); //interner Pull-up an PA6 aktivieren
};
}
//DMX Empfangen
ISR (USART_RX_vect)
{
static unsigned int dmx_channel_rx_count = 0;
static unsigned char dmx_valid = 0;
unsigned char recv = 0;
recv = UDR;
if(UCSRA&(1<<FE))
{
if(dmx_channel_rx_count > 1)
{
dmx_lost = 0;
}
dmx_channel_rx_count = 0;
dmx_buffer[0] = recv;
if(dmx_buffer[0] == 0)
{
dmx_valid = 1;
dmx_channel_rx_count++;
}
else
{
dmx_valid = 0;
}
return;
}
//Test da DMX einen Fehler geworfen hat
dmx_valid = 1;
if(dmx_valid)
{
//PUMP_ON;
if(dmx_channel_rx_count == dmx_adresse) dmx_buffer[1] = recv;
if(dmx_channel_rx_count < 514)
{
dmx_channel_rx_count++;
}
//PUMP_OFF;
return;
}
}
ISR (TIMER0_COMPA_vect)
{
static unsigned char pwm_counter = 0;
pwm_counter++;
if(pwm_counter == 255)
{
pwm_counter = 0;
}
if(dmx_lost<DMX_LOST_TIMEOUT)
{
dmx_lost++;
}
}
ISR (TIMER1_COMPA_vect) {
OCR1A = OCRx_RELOAD; //Timer neu laden
if (T == 80) {
int16_t z;
//Störgrößenaufschaltung bei niedriger Temperatur
if (temperature < 4300) {
if (PUMP < 32) {z = PUMP * 1024;} else {z = 32767;}; //Pumpenleistung bestimmen
} else {z = 0;}; //Bei kleinerer temperatur wird Störgröße aufgeschaltet //32 entspricht 32000 sollleistung
PWM = pid_Controller(setPoint, temperature, z, &pidData); //SetPoint = tsoll, processValue = tist errorValue = Pumpenleistung
T=0;
}
T++; //PWM mit 80 schritten
//Heizung schalten
if (T < (PWM / Factor)) {HEATER_ON;} else {HEATER_OFF;};
//Pumpe mit PWM einschalten, falls temperatur > 250° und kleiner 300°C
if (T < (PUMP / 4) && (temperature > 4000) && (temperature < 4500)) {PUMP_ON;} else {PUMP_OFF;};
}
//Hauptprogramm
int main (void)
{
//Init usart
UBRRH = UBRR_VAL >> 8;
UBRRL = UBRR_VAL & 0xFF;
UCSRB|=(1 << RXEN | 1<< RXCIE);
UCSRC|=(1<<USBS);
//Inputs setzen
DDRD &= ~(1 << PD6); // switch input pin
PORTD |= (1 << PD6); // enable pull-up resistor
DDRB &= ~(1 << PB2); // switch input pin
PORTB |= (1 << PB2); // enable pull-up resistor
DDRD &= ~(1 << PD5); // switch input pin
PORTD |= (1 << PD5); // enable pull-up resistor
DDRD &= ~(1 << PD4); // switch input pin
PORTD |= (1 << PD4); // enable pull-up resistor
DDRD &= ~(1 << PD3); // switch input pin
PORTD |= (1 << PD3); // enable pull-up resistor
DDRD &= ~(1 << PD2); // switch input pin
PORTD |= (1 << PD2); // enable pull-up resistor
DDRD &= ~(1 << PD1); // switch input pin
PORTD |= (1 << PD1); // enable pull-up resistor
DDRB &= ~(1 << PB0); // switch input pin
PORTB |= (1 << PB0); // enable pull-up resistor
//DMX-Adresse einlesen;
// dmx_adresse = 0;
if (PINB & (1 << PB0)) dmx_adresse =1;
if (PIND & (1 << PD6)) dmx_adresse +=128;
if (PINB & (1 << PB2)) dmx_adresse +=64;
if (PIND & (1 << PD5)) dmx_adresse +=32;
if (PIND & (1 << PD4)) dmx_adresse +=16;
if (PIND & (1 << PD3)) dmx_adresse +=8;
if (PIND & (1 << PD2)) dmx_adresse +=4;
if (PIND & (1 << PD1)) dmx_adresse +=2;
//PID Konfigurieren:
pid_Init(p_factor, i_factor , d_factor , &pidData);
// Timer 1 freigeben
TCCR1B = (1<<WGM12)| (1<<CS12) | (1<<CS10); //Vorteiler 1024
OCR1A = OCRx_RELOAD;
// OCR1A Interrupt freigeben, wird für Timer CTC mode benutzt
TIMSK = 1<<OCIE1A;
// DDRD |=(1<<PD2);
// PORTD &=~(1<<PD2);
HEATER_PIN_OUT;
PUMP_PIN_OUT;
enable_spi(1);
sei();
while(1)
{
if(dmx_lost==DMX_LOST_TIMEOUT)
{
dmx_buffer[1] = 0;
};
PUMP = dmx_buffer[1];
temperature = spi();
if (temperature > 4600) Fehler();
}
}