Compare commits

...

58 Commits

Author SHA1 Message Date
24ef8ce70d add prints 2023-01-12 18:03:57 +01:00
701ae5501a fix spooling bug 2023-01-12 18:03:21 +01:00
4ba5a3c39f modbus/kraftsensor cleanup 2023-01-12 17:51:22 +01:00
2f5f57546a change button fine ajdustments 2023-01-12 17:40:29 +01:00
3f662045e6 less aggressive pid 2022-09-21 14:37:47 +02:00
18d2ae2f3c add start/stop when brake is engaged 2022-09-21 14:36:28 +02:00
c62792a864 zero sensor value when both buttons pressed 2022-09-05 17:10:22 +02:00
0b5dc619a6 changes for 1:5 gear instead of 1:10 2022-09-05 17:09:24 +02:00
21099092c0 increse control var to 32bit, decrease Hysteresis 2022-09-05 15:58:33 +02:00
93debb7dd6 add comments 2022-09-05 15:57:42 +02:00
393da679e0 adjust regulator (more agressive p) 2022-09-05 15:56:18 +02:00
e938862cde fix bug where regulator locks on overflown integer 2022-07-28 18:31:55 +02:00
560b4fbc4d fix limit bug 2022-07-28 18:14:34 +02:00
012f133dbe new spooling speed regulation
still needs some tuning
2022-05-24 19:56:02 +02:00
daadb91055 change function call name 2022-05-24 19:49:43 +02:00
6fbc0d4c08 check init when spooling is stopped 2022-05-24 19:43:11 +02:00
39f9c1691a move initial send_settings out of main loop 2022-05-24 19:35:45 +02:00
b37d685690 disable spike detection
false sensor readings should be fixed by commit 105b208bed in hx711 repo
2022-05-24 19:27:32 +02:00
14850ae8e9 reduce timeout value on modbus 2022-05-24 19:24:35 +02:00
e514d57ddf getter method for abzug_state 2022-05-24 19:03:10 +02:00
dcf1531033 manual spooling when button is held down 2022-05-24 19:01:38 +02:00
1ad6f56a9d send less mqtt msgs, improve performance 2022-05-19 21:01:01 +02:00
cf5cdfc79f increase baud rate for performance 2022-05-19 19:16:42 +02:00
59fa66e164 reduce ISR time from 4.5us to 1.6us 2022-05-19 17:33:12 +02:00
53ceb7a0ba reduce isr time from 16us to 6us 2022-05-19 17:16:12 +02:00
c861a8b58a new nachlauf code 2022-04-07 20:53:52 +02:00
1aa6b17065 faster moving speed 2022-04-06 00:22:31 +02:00
1a8b4418a6 change programmer 2022-04-06 00:21:17 +02:00
f2fd5c52fa add nachlaufwinkel 2022-04-06 00:20:59 +02:00
32ee1da8e8 limit spooling speed 2022-04-06 00:18:55 +02:00
5e9d3578a1 set homing speed before homing 2022-04-06 00:12:43 +02:00
93f0ef3759 send taenzer to start position when init pressed 2022-04-06 00:10:27 +02:00
690f4b308a add active state for taenzer 2022-04-06 00:08:32 +02:00
b2721c0123 reenable error counter and indentation 2022-04-06 00:03:48 +02:00
76f3fd1d5a set homing speed in a better location 2022-04-05 21:56:40 +02:00
721689c525 make spooling speed controled instead of manual 2022-04-05 13:12:14 +02:00
c4181a27e2 update timer1 in README 2022-04-05 12:53:37 +02:00
b88d9fb85c send spool rpm 2022-04-04 16:18:26 +02:00
349962b454 decrease homing speed for better homing 2022-04-04 15:41:20 +02:00
836d2e3e6e add pid controller 2022-04-04 15:39:54 +02:00
eb680bac89 add direction change on layer finish 2022-04-04 15:26:14 +02:00
22a8b37713 change default spooling speed 2022-04-04 15:24:24 +02:00
5a85471ca5 dont start moving if already homed 2022-04-04 15:22:33 +02:00
5ff3793991 make force setpoint adjustable 2022-04-04 15:21:34 +02:00
6601ae39f9 add missing include 2022-04-04 15:14:11 +02:00
aa30d70cd6 change change reference to renamed function 2022-04-04 15:13:19 +02:00
b2ef7d8240 fix volatile error 2022-04-02 17:23:11 +02:00
76bca5f039 add translatoric axis 2022-04-02 17:19:16 +02:00
678d40709d add globaly available notaus-state 2022-04-02 16:47:58 +02:00
a33902424e light error lamp when not ready 2022-04-02 16:46:40 +02:00
93de6e725c increase modbus poll rate 2022-04-02 16:37:12 +02:00
1645f2c37c change mqtt client id 2022-04-02 16:36:36 +02:00
566b96c8b3 send dance roll position in percent 2022-04-02 16:32:38 +02:00
c9b79e7339 fix overflow 2022-04-02 16:27:50 +02:00
a103131163 add reset target 2022-04-02 16:26:10 +02:00
db6f03ef97 fix modbus timeout 2022-04-02 16:25:32 +02:00
54572ac7f2 introduce (crude) false-reading detection 2022-04-02 16:23:48 +02:00
f8f515dc59 reverse endianess for modbus read 2022-04-02 16:22:19 +02:00
17 changed files with 520 additions and 122 deletions

View File

@@ -4,9 +4,9 @@ FILES = $(SRCS:%.c=%) #main uart avrIOhelper/io-helper #uart#hier alle c-Datei
MCU = atmega2560 MCU = atmega2560
PROGC = m2560 PROGC = m2560
CC = avr-gcc CC = avr-gcc
#TOOL = atmelice_isp TOOL = atmelice_isp
#TOOL = avrispmkii #TOOL = avrispmkii
TOOL = usbasp-clone #TOOL = usbasp-clone
BUILDDIR = Builds BUILDDIR = Builds
@@ -37,6 +37,9 @@ load: $(BUILDDIR)/$(TARGET).hex
avrdude -p $(PROGC) -c $(TOOL) -U flash:w:$(BUILDDIR)/$(TARGET).hex -v -B 1MHz avrdude -p $(PROGC) -c $(TOOL) -U flash:w:$(BUILDDIR)/$(TARGET).hex -v -B 1MHz
program: clean load program: clean load
reset:
avrdude -p $(PROGC) -c $(TOOL)
size: $(BUILDDIR)/$(TARGET).elf size: $(BUILDDIR)/$(TARGET).elf
avr-size -C --mcu=$(MCU) $(BUILDDIR)/$(TARGET).elf avr-size -C --mcu=$(MCU) $(BUILDDIR)/$(TARGET).elf

View File

@@ -32,7 +32,7 @@
|Timer| Type | Usage | Mode | used ISRs | Output connected |Timer| Type | Usage | Mode | used ISRs | Output connected
|-----|--------|-------------------------------|------------------------|----------------|------------------ |-----|--------|-------------------------------|------------------------|----------------|------------------
| 0 | 8 bit | Millis Tick Timer (1kHz) | 2 (CTC) | COMPA | - | 0 | 8 bit | Millis Tick Timer (1kHz) | 2 (CTC) | COMPA | -
| 1 | 16 bit | | | | | 1 | 16 bit | Step Signal Translation Spule | 8 (PWM, Phase & Freq.) | OVF | OC1A / PB5
| 2 | 8 bit | Modbus Tick Timer (10kHz) | 2 (CTC) | COMPA | - | 2 | 8 bit | Modbus Tick Timer (10kHz) | 2 (CTC) | COMPA | -
| 3 | 16 bit | Step Signal Abzugsrolle | 8 (PWM, Phase & Freq.) | - | OC3B / PE4 | 3 | 16 bit | Step Signal Abzugsrolle | 8 (PWM, Phase & Freq.) | - | OC3B / PE4
| 4 | 16 bit | Step Signal Taenzer | 8 (PWM, Phase & Freq.) | OVF, ~~COMPA~~ | OC4A / PH3 | 4 | 16 bit | Step Signal Taenzer | 8 (PWM, Phase & Freq.) | OVF, ~~COMPA~~ | OC4A / PH3

57
abzug.c
View File

@@ -1,5 +1,7 @@
#include <avr/io.h> #include <avr/io.h>
#include <stdint.h>
#include "avrIOhelper/io-helper.h" #include "avrIOhelper/io-helper.h"
#include "common.h"
uint16_t abzug_speed = 100; uint16_t abzug_speed = 100;
@@ -14,15 +16,18 @@ void timer3_init()
DDRE |= 1 << 4; DDRE |= 1 << 4;
} }
uint8_t get_abzug_state(){
return TCCR3B & _BV(CS31);
}
void send_abzug_speed(void); extern void send_settings(void);
void do_abzug(){ void do_abzug(){
if (read_Input(BTN_ABZUG_EIN, RISING)) { if (read_Input(BTN_ABZUG_EIN, RISING)) {
TCCR3B |= _BV(CS31); TCCR3B |= _BV(CS31);
set_Output(LED_ABZUG, ON); set_Output(LED_ABZUG, ON);
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
send_abzug_speed(); send_settings();
#endif #endif
} }
@@ -30,47 +35,47 @@ void do_abzug(){
TCCR3B &= ~(_BV(CS31)); TCCR3B &= ~(_BV(CS31));
set_Output(LED_ABZUG, OFF); set_Output(LED_ABZUG, OFF);
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
send_abzug_speed(); send_settings();
#endif #endif
} }
if (read_Input(BTN_ABZUG_PLUS, RISING)) { if (read_Input(BTN_ABZUG_PLUS, RISING)) {
if(abzug_speed <= 900)
abzug_speed += 100;
else
abzug_speed = 1000;
#if PLC_MQTT_ENABLED
send_abzug_speed();
#endif
}
if (read_Input(BTN_ABZUG_MINUS, RISING)) {
if(abzug_speed >= 110)
abzug_speed -= 100;
else
abzug_speed = 10;
#if PLC_MQTT_ENABLED
send_abzug_speed();
#endif
}
if (read_Input(BTN_ABZUG_PLUS_FEIN, RISING)) {
if(abzug_speed <= 990) if(abzug_speed <= 990)
abzug_speed += 10; abzug_speed += 10;
else else
abzug_speed = 1000; abzug_speed = 1000;
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
send_abzug_speed(); send_settings();
#endif #endif
} }
if (read_Input(BTN_ABZUG_MINUS_FEIN, RISING)) { if (read_Input(BTN_ABZUG_MINUS, RISING)) {
if(abzug_speed >= 20) if(abzug_speed >= 20)
abzug_speed -= 10; abzug_speed -= 10;
else else
abzug_speed = 10; abzug_speed = 10;
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
send_abzug_speed(); send_settings();
#endif
}
if (read_Input(BTN_ABZUG_PLUS_FEIN, RISING)) {
if(abzug_speed <= 999)
abzug_speed += 1;
else
abzug_speed = 1000;
#if PLC_MQTT_ENABLED
send_settings();
#endif
}
if (read_Input(BTN_ABZUG_MINUS_FEIN, RISING)) {
if(abzug_speed >= 11)
abzug_speed -= 1;
else
abzug_speed = 10;
#if PLC_MQTT_ENABLED
send_settings();
#endif #endif
} }

View File

@@ -1,9 +1,12 @@
#ifndef _ABZUG_H #ifndef _ABZUG_H
#define _ABZUG_H #define _ABZUG_H
#include <stdint.h>
extern uint16_t abzug_speed; extern uint16_t abzug_speed;
void do_abzug(void); void do_abzug(void);
void timer3_init(void); void timer3_init(void);
uint8_t get_abzug_state(void);
#endif #endif

View File

@@ -93,6 +93,7 @@ void ioHelperEdgeDetector(void);
// Schrittmotoren richtung // Schrittmotoren richtung
#define MOTOR_TAENZER_DIR BitPH4 #define MOTOR_TAENZER_DIR BitPH4
#define MOTOR_TRANS_DIR BitPB6
#define LED_INIT BitPE3 #define LED_INIT BitPE3
#define LED_ABZUG BitPL6 #define LED_ABZUG BitPL6
@@ -147,6 +148,12 @@ void ioHelperEdgeDetector(void);
#define BTN_SPULENWECHSEL BitPinK0 #define BTN_SPULENWECHSEL BitPinK0
#define BTN_INIT BitPinF4 #define BTN_INIT BitPinF4
#define BTN_KRAFT_PLUS BitPinD7
#define BTN_KRAFT_MINUS BitPinG2
#define IN_TAENZER_HOME BitPinF0 #define IN_TAENZER_HOME BitPinF0
#define IN_SPULE_HOME BitPinF1
#define IN_BREMSE_STATE BitPinF2
#endif #endif

View File

@@ -1,4 +1,6 @@
#include <avr/io.h> #include <avr/io.h>
#include <stdint.h>
#include <stdlib.h>
#include <util/delay.h> #include <util/delay.h>
#include <stdio.h> #include <stdio.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
@@ -10,6 +12,8 @@
int32_t kraftsensor_value; int32_t kraftsensor_value;
uint8_t kraftsensor_valid; uint8_t kraftsensor_valid;
int32_t kraftsensor_zero_offset = 0/*197700*/;
void timer2_init() void timer2_init()
{ {
TCCR2A = (1<<WGM21); //TIMER0 SET-UP: CTC MODE TCCR2A = (1<<WGM21); //TIMER0 SET-UP: CTC MODE
@@ -35,23 +39,23 @@ void do_kraftsensor(){
} }
else{ else{
kraftsensor_valid = 1; kraftsensor_valid = 1;
int32_t tmp = (uint32_t)m_data[0]<<16; int32_t tmp = (uint32_t)m_data[1]<<16;
tmp |= m_data[1]; tmp |= m_data[0];
/* conversion magic to milliNewton */ /* conversion magic to milliNewton */
kraftsensor_value = ((tmp + 539363)*9.81)/177.380; kraftsensor_value = (((tmp /* + 539363*/)*9.81)/177.380)+kraftsensor_zero_offset;
} }
} }
uint8_t wait_receive(uint8_t len, uint16_t dest[], uint8_t timeout){ int8_t wait_receive(uint8_t len, uint16_t dest[], uint8_t timeout){
uint8_t breaker = timeout; uint8_t breaker = timeout;
while(!receiveOkay && breaker) { //wait for client response, time out after 1s while(!receiveOkay && breaker) { //wait for client response, time out after 1s
breaker--; breaker--;
_delay_ms(1); _delay_ms(1);
if(breaker==0)
return -1;
} }
printf("breaker: %d\n\r", breaker);
if(receiveOkay) { //if this fails, there was either no response or a crc error if(receiveOkay) { //if this fails, there was either no response or a crc error
if(rxbuffer[1]&0x80) { //client responded with an error code if(rxbuffer[1]&0x80) { //client responded with an error code
@@ -68,6 +72,23 @@ uint8_t wait_receive(uint8_t len, uint16_t dest[], uint8_t timeout){
return 0; return 0;
} }
int8_t wait_write(uint8_t timeout){
uint8_t breaker = timeout;
while(!receiveOkay && breaker) { //wait for client response, time out after 1s
breaker--;
_delay_ms(1);
if(breaker==0)
return -1;
}
if(receiveOkay) { //if this fails, there was either no response or a crc error
if(rxbuffer[1]&0x80) { //client responded with an error code
return rxbuffer[1]&0x80;
}
}
return 0;
}
void readReg(uint8_t slaveid, uint16_t address, uint8_t amount) { void readReg(uint8_t slaveid, uint16_t address, uint8_t amount) {
_delay_ms(2); _delay_ms(2);
rxbuffer[0]=slaveid; rxbuffer[0]=slaveid;
@@ -93,5 +114,7 @@ void writeReg(uint8_t slaveid, uint16_t address, uint16_t value) {
} }
ISR(TIMER2_COMPA_vect) { //this ISR is called 9765.625 times per second ISR(TIMER2_COMPA_vect) { //this ISR is called 9765.625 times per second
//PORTH &= ~(1<<5);
modbusTickTimer(); modbusTickTimer();
//PORTH |= (1<<5);
} }

View File

@@ -8,10 +8,12 @@
extern int32_t kraftsensor_value; extern int32_t kraftsensor_value;
extern uint8_t kraftsensor_valid; extern uint8_t kraftsensor_valid;
extern int32_t kraftsensor_zero_offset;
void timer2_init(); void timer2_init();
void kraftsensor_init(); void kraftsensor_init();
void do_kraftsensor(void); void do_kraftsensor(void);
uint8_t wait_receive(uint8_t len, uint16_t dest[], uint8_t timeout); int8_t wait_receive(uint8_t len, uint16_t dest[], uint8_t timeout);
void readReg(uint8_t slaveid, uint16_t address, uint8_t amount); void readReg(uint8_t slaveid, uint16_t address, uint8_t amount);
void writeReg(uint8_t slaveid, uint16_t address, uint16_t value); void writeReg(uint8_t slaveid, uint16_t address, uint16_t value);

87
main.c
View File

@@ -1,6 +1,8 @@
#include <avr/io.h> #include <avr/io.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include <avr/wdt.h> #include <avr/wdt.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h> #include <string.h>
#include <stdlib.h> #include <stdlib.h>
@@ -71,8 +73,37 @@ static void avr_init()
return; return;
} }
void send_info(void){ // send processvalues that are constantly changing
char msg[4]; void send_values(void){
char msg[10];
/* Taenzer */
if(kraftsensor_valid)
ltoa(kraftsensor_value, msg, 10);
else
msg[0] = '0';
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/taenzer/pv_kraft", msg, strlen(msg));
int8_t temp = taenzer_state.pos / 10000;
ltoa(temp, msg, 10);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/taenzer/pos", msg, strlen(msg));
itoa((250*60)/ICR5, msg, 10);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/spule/speed", msg, strlen(msg));
sprintf(msg, "%d", windings);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/spule/windings", msg, strlen(msg));
sprintf(msg, "%ld", spule_trans_pos);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/spule/trans_pos", msg, strlen(msg));
}
// send settings wich only change on buttion press
void send_settings(void){
//TODO only send on change or improve performance otherwise
char msg[10];
/* Abzug */
sprintf(msg, "%d", abzug_speed); sprintf(msg, "%d", abzug_speed);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/abzug/speed", msg, strlen(msg)); mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/abzug/speed", msg, strlen(msg));
@@ -82,17 +113,20 @@ void send_info(void){
sprintf(msg, "False"); sprintf(msg, "False");
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/abzug/onoff", msg, strlen(msg)); mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/abzug/onoff", msg, strlen(msg));
if(kraftsensor_valid) /* Taenzer */
ltoa(kraftsensor_value, msg, 10); itoa(taenzer_state.force_setpoint, msg, 10);
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/taenzer/sp_kraft", msg, strlen(msg));
/* Spule */
if(TCCR5B & (1<<CS31))
sprintf(msg, "True");
else else
msg[0] = '0'; sprintf(msg, "False");
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/kraft", msg, strlen(msg)); mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/spule/onoff", msg, strlen(msg));
ltoa(taenzer_state.pos, msg, 10); ///* Uptime */
mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/speicher/pos", msg, strlen(msg)); //sprintf(msg, "%ld", millis()/1000);
//mqtt_pub(&mqtt_client, "/Filamentanlage/05_Abzug/state/uptime", msg, strlen(msg));
sprintf(msg, "%ld", millis()/1000);
mqtt_pub(&mqtt_client, "/Filamentanlage/04_Abzug/state/uptime", msg, strlen(msg));
} }
@@ -106,6 +140,9 @@ int main()
printf("moin!\n\r"); printf("moin!\n\r");
set_Output(LED_FEHLER, ON);
timer1_init(); //translation
timer3_init(); //abzug timer3_init(); //abzug
timer4_init(); //taenzer timer4_init(); //taenzer
timer5_init(); //spule timer5_init(); //spule
@@ -134,7 +171,7 @@ int main()
MQTTPacket_connectData data = MQTTPacket_connectData_initializer; MQTTPacket_connectData data = MQTTPacket_connectData_initializer;
data.willFlag = 0; data.willFlag = 0;
data.MQTTVersion = 4;//3; data.MQTTVersion = 4;//3;
data.clientID.cstring = (char*)"controllino"; data.clientID.cstring = (char*)"controllino_aufspuleinheit";
data.username.cstring = (char*)"Aufspuleinheit"; data.username.cstring = (char*)"Aufspuleinheit";
data.password.cstring = (char*)"\0"; data.password.cstring = (char*)"\0";
data.keepAliveInterval = 10; data.keepAliveInterval = 10;
@@ -162,15 +199,17 @@ int main()
uint32_t timer_send_info = millis(); uint32_t timer_send_info = millis();
uint32_t timer_modbus_poll = millis(); uint32_t timer_modbus_poll = millis();
while(1) set_Output(LED_FEHLER, OFF);
{
wdt_reset(); // WDT reset at least every sec
set_Output(BitPH5, ON); //DEBUG
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
if(millis() < 10) send_settings();
send_info();
#endif #endif
while(1){
wdt_reset(); // WDT reset at least every sec
ioHelperReadPins(); ioHelperReadPins();
ioHelperDebounce(); ioHelperDebounce();
ioHelperEdgeDetector(); ioHelperEdgeDetector();
@@ -182,18 +221,20 @@ int main()
outStates[2] ^= outStatesBlinking[2]; outStates[2] ^= outStatesBlinking[2];
outStates[3] ^= outStatesBlinking[3]; outStates[3] ^= outStatesBlinking[3];
timer_blink_outs = millis(); timer_blink_outs = millis();
//printf("icr5: %u\n", ICR5);
} }
if(millis() - timer_modbus_poll > 100){ if(millis() - timer_modbus_poll > 20){
do_kraftsensor(); do_kraftsensor(); // 8ms !!!
timer_modbus_poll += 100; timer_modbus_poll += 20;
} }
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
// send misc info // send misc info
if(millis() - timer_send_info > 200){ if(millis() - timer_send_info > 200){
timer_send_info += 200; timer_send_info += 200;
send_info(); send_values(); // 10ms
//send_info(); // 27ms every 200ms
} }
#endif #endif
@@ -205,10 +246,10 @@ int main()
#if PLC_MQTT_ENABLED #if PLC_MQTT_ENABLED
ioHelperSetBit(outStates, LED_BUS_OK, 1); ioHelperSetBit(outStates, LED_BUS_OK, 1);
ioHelperSetOuts(); ioHelperSetOuts();
MQTTYield(&mqtt_client, 10); //blocking call MQTTYield(&mqtt_client, 1); //blocking call
ioHelperSetBit(outStates, LED_BUS_OK, 0); ioHelperSetBit(outStates, LED_BUS_OK, 0);
#endif #endif
ioHelperSetOuts(); ioHelperSetOuts(); //40us
} }
return 0; return 0;
} }

View File

@@ -52,7 +52,7 @@ THE POSSIBILITY OF SUCH DAMAGE.
/* define baudrate of modbus */ /* define baudrate of modbus */
#ifndef BAUD #ifndef BAUD
#define BAUD 38400L #define BAUD 115200L
#endif #endif
/* /*

54
mqtt.c
View File

@@ -35,32 +35,32 @@ void messageArrived(MessageData* md)
void mqtt_pub(Client* mqtt_client, char * mqtt_topic, char * mqtt_msg, int mqtt_msg_len) void mqtt_pub(Client* mqtt_client, char * mqtt_topic, char * mqtt_msg, int mqtt_msg_len)
{ {
//static uint32_t mqtt_pub_count = 0; //static uint32_t mqtt_pub_count = 0;
//static uint8_t mqtt_err_cnt = 0; static uint8_t mqtt_err_cnt = 0;
int32_t mqtt_rc; int32_t mqtt_rc;
//printf(">>MQTT pub msg nr%lu ", ++mqtt_pub_count); //printf(">>MQTT pub msg nr%lu ", ++mqtt_pub_count);
MQTTMessage pubMessage; MQTTMessage pubMessage;
pubMessage.qos = QOS0; pubMessage.qos = QOS0;
pubMessage.id = mes_id++; pubMessage.id = mes_id++;
pubMessage.payloadlen = (size_t)mqtt_msg_len; pubMessage.payloadlen = (size_t)mqtt_msg_len;
pubMessage.payload = mqtt_msg; pubMessage.payload = mqtt_msg;
mqtt_rc = MQTTPublish(mqtt_client, mqtt_topic , &pubMessage); mqtt_rc = MQTTPublish(mqtt_client, mqtt_topic , &pubMessage);
//Analize MQTT publish result (for MQTT failover mode) //Analize MQTT publish result (for MQTT failover mode)
if (mqtt_rc == SUCCESSS) if (mqtt_rc == SUCCESSS)
{ {
//mqtt_err_cnt = 0; mqtt_err_cnt = 0;
//printf(" - OK\r\n"); //printf(" - OK\r\n");
} }
else else
{ {
printf("mqtt pub - ERROR\r\n"); //while(1);
printf("Connection with MQTT Broker was lost!!\r\nReboot the board..\r\n"); //Reboot device after 20 continuous errors (~ 20sec)
while(1); if(mqtt_err_cnt++ > 10)
//Reboot device after 20 continuous errors (~ 20sec) {
//if(mqtt_err_cnt++ > 20) printf("mqtt pub - ERROR\r\n");
//{ printf("Connection with MQTT Broker was lost!!\r\nReboot the board..\r\n");
// while(1); while(1);
//} }
} }
} }

View File

@@ -1,10 +1,16 @@
#include "kraftsensor.h" #include "kraftsensor.h"
#include "avrIOhelper/io-helper.h" #include "avrIOhelper/io-helper.h"
#include <stdint.h>
#include <stdio.h> #include <stdio.h>
#include "notaus.h"
uint8_t notaus_state = POWER_OFF;
void do_notaus(){ void do_notaus(){
if(!read_Input(IN_NOTAUS_ANLAGE, LEVEL) || read_Input(IN_NOTAUS_SCHRANK, LEVEL) || read_Input(IN_NOTAUS_DISPLAY, LEVEL)){ if(!read_Input(IN_NOTAUS_ANLAGE, LEVEL) || read_Input(IN_NOTAUS_SCHRANK, LEVEL) || read_Input(IN_NOTAUS_DISPLAY, LEVEL)){
/* at least on pressed */ /* at least one pressed */
notaus_state = POWER_OFF;
ioHelperSetBit(outStates, AMPEL_ROT, 1); ioHelperSetBit(outStates, AMPEL_ROT, 1);
ioHelperSetBit(outStates, AMPEL_GELB, 0); ioHelperSetBit(outStates, AMPEL_GELB, 0);
ioHelperSetBit(outStates, AMPEL_GRUEN, 0); ioHelperSetBit(outStates, AMPEL_GRUEN, 0);
@@ -34,6 +40,8 @@ void do_notaus(){
} }
else if(!read_Input(IN_ANLAGE_EIN, LEVEL)){ else if(!read_Input(IN_ANLAGE_EIN, LEVEL)){
/* nothing pressed, but power not on */ /* nothing pressed, but power not on */
notaus_state = ARMED;
ioHelperSetBit(outStates, AMPEL_ROT, 0); ioHelperSetBit(outStates, AMPEL_ROT, 0);
ioHelperSetBit(outStates, AMPEL_GELB, 1); ioHelperSetBit(outStates, AMPEL_GELB, 1);
ioHelperSetBit(outStates, AMPEL_GRUEN, 0); ioHelperSetBit(outStates, AMPEL_GRUEN, 0);
@@ -48,6 +56,8 @@ void do_notaus(){
} }
else{ else{
/* powered on */ /* powered on */
notaus_state = POWER_ON;
ioHelperSetBit(outStates, AMPEL_ROT, 0); ioHelperSetBit(outStates, AMPEL_ROT, 0);
ioHelperSetBit(outStates, AMPEL_GELB, 0); ioHelperSetBit(outStates, AMPEL_GELB, 0);
ioHelperSetBit(outStates, AMPEL_GRUEN, 1); ioHelperSetBit(outStates, AMPEL_GRUEN, 1);

View File

@@ -1,6 +1,14 @@
#ifndef _NOTAUS_H_ #ifndef _NOTAUS_H_
#define _NOTAUS_H_ #define _NOTAUS_H_
#include <stdint.h>
#define POWER_ON 2
#define ARMED 1
#define POWER_OFF 0
extern uint8_t notaus_state;
void do_notaus(void); void do_notaus(void);
#endif #endif

34
pid_controller.h Normal file
View File

@@ -0,0 +1,34 @@
/*
* pid_controller.h
*
* Created on: Apr 24, 2016
* Author: subham roy
*/
#ifndef __PID_CONTROLLER_H
#define __PID_CONTROLLER_H
typedef struct {
/* PID controller parameters */
double Kp;
double Ki;
double Kd;
/* max output limits for the PID controller */
double output_max;
double output_min;
/* below are session variables for the PID controller */
double _integral_sum;
double _prev_err;
double _dt;
} PID_vars;
#define PID_VARS_INIT(x) PID_vars x = {.Kp=1.3,.Ki=0.00,.Kd=0.00,.output_max=25000.0, \
.output_min=-25000.0,._integral_sum=0.0,._prev_err=0.0,._dt=1.0}
/* Function Prototypes */
double pid(PID_vars *vars, double current_err);
#endif

207
spule.c
View File

@@ -1,30 +1,215 @@
#include <avr/io.h> #include <avr/io.h>
#include <avr/interrupt.h>
#include <stdint.h>
#include <stdio.h>
#include "avrIOhelper/io-helper.h" #include "avrIOhelper/io-helper.h"
#include "taenzer.h"
#include "abzug.h"
volatile uint16_t windings = 0;
volatile uint16_t windings_wakeup = 0;
volatile uint8_t trans_state = 0;
int32_t spule_trans_pos = 0;
uint8_t spule_trans_homed = 0;
#define TRANS_ROT_FACTOR 0.14
void timer1_init()
{
TCCR1A |= (1<<COM1A1);
TCCR1B |= _BV(WGM13);
ICR1 = 100;
OCR1A = 50;
DDRB |= 1 << 5;
TIMSK1 |= 1<<TOIE1;
}
void timer5_init() void timer5_init()
{ {
TCCR5A |= (1<<COM5C1); TCCR5A |= (1<<COM5C1);
TCCR5B |= _BV(WGM53); TCCR5B |= _BV(WGM53);
ICR5 = 500; ICR5 = 1000;
OCR5C = 250; OCR5C = 500;
DDRL |= 1 << 5; DDRL |= 1 << 5;
TIMSK5 |= 1<<TOIE5;
}
static void spule_onoff(uint8_t state){
if(state){
TCCR5B |= _BV(CS51); // ROTATION
TCCR1B |= _BV(CS11); // TRANSLATION
}
else{
TCCR5B &= ~(_BV(CS51));
TCCR1B &= ~(_BV(CS11));
}
}
void set_spooling_speed(uint16_t speed){
ICR5=speed;
OCR5C = ICR5/2;
ICR1 = ICR5/TRANS_ROT_FACTOR;
OCR1A = ICR1/2;
} }
void do_spule(){ void do_spule(){
if (read_Input(BTN_WICKELN_EIN, RISING)) { // Translatoric axis homeing code
TCCR5B |= _BV(CS51); //TURN ON if(read_Input(IN_SPULE_HOME, LEVEL) && spule_trans_homed == 0){
spule_trans_homed = 1;
spule_trans_pos = 0;
TCCR1B &= ~(_BV(CS11));
set_Output(MOTOR_TRANS_DIR, 0); // direction: back
ICR1 = ICR5/TRANS_ROT_FACTOR;
OCR1A = ICR1/2;
} }
if (read_Input(BTN_WICKELN_AUS, RISING)) {
TCCR5B &= ~(_BV(CS51)); // if not homed goto home
if(!spule_trans_homed){
ICR1 = 100;
OCR1A = 50;
set_Output(MOTOR_TRANS_DIR, 1); // direction: front
TCCR1B |= _BV(CS11); //TURN ON
} }
if (read_Input(BTN_TAENZER_START, RISING)) {
ICR5-=15; // manual forwarding if button is held
else if(!get_abzug_state() || (get_abzug_state() && read_Input(IN_BREMSE_STATE, LEVEL)) ){
if(read_Input(BTN_WICKELN_EIN, LEVEL)){
set_spooling_speed(300);
spule_onoff(1);
}
else
spule_onoff(0);
}
// normal operation
else{
/* speed regulation - keep taenzer at 10% */
float p = 100.0/(int32_t)(taenzer_state.pos/1000);
p-=1;
p/=2;
p+=1;
//tmp = (int32_t)(taenzer_state.pos/10000);
//printf("%ld\n", tmp);
//printf("temp1: %d\n", tmp);
//TODO fix bounds
//if(tmp < -7500/abzug_speed/2)
// tmp = -7500/abzug_speed/2;
//printf("temp2: %d\n", tmp);
if(p < 0.5)
p = 0.5;
if(p > 2)
p = 2;
uint16_t base_speed = (14000/abzug_speed);
uint16_t ctrl_speed = base_speed * p;
if(ctrl_speed <= 70)
ctrl_speed = 70;
ICR5 = ctrl_speed;
OCR5C = ICR5/2; OCR5C = ICR5/2;
if(trans_state != 4)
ICR1 = ICR5/TRANS_ROT_FACTOR;
else
ICR1 = 0.5*(ICR5/TRANS_ROT_FACTOR);
OCR1A = ICR1/2;
if (read_Input(BTN_WICKELN_EIN, RISING) && !read_Input(IN_BREMSE_STATE, LEVEL)) {
spule_onoff(1);
}
if (read_Input(BTN_WICKELN_AUS, RISING)) {
spule_onoff(0);
}
} }
if (read_Input(BTN_SPULENWECHSEL, RISING)) { if (read_Input(BTN_INIT, RISING)) {
ICR5+=15; spule_trans_homed = 0;
OCR5C = ICR5/2; taenzer_state.homed = 0;
taenzer_state.active = 0;
windings = 0;
windings_wakeup = 0;
} }
if (read_Input(IN_BREMSE_STATE, FALLING)) {
printf("draußen\n");
spule_onoff(1);
}
if (read_Input(IN_BREMSE_STATE, RISING)) {
printf("drinne\n");
spule_onoff(0);
}
//PORTH |= (1<<5);
}
ISR(TIMER1_OVF_vect) {
//PORTH &= ~(1<<5);
//if(ioHelperReadBit(outStates, MOTOR_TRANS_DIR)){
if(PORTB & (1<<6)){
spule_trans_pos -= 1;
}
else{
spule_trans_pos += 1;
}
//TODO keep track if position stays in bounds
//PORTH |= (1<<5);
}
ISR(TIMER5_OVF_vect) {
//PORTH &= ~(1<<5);
static uint16_t steps = 0;
steps++;
if(steps == 25000){
windings++;
steps=0;
printf("windungen: %d\t", windings);
printf("trans pos: %ld\n", spule_trans_pos);
printf("speed %d\n", ICR1);
}
if(windings == windings_wakeup){
TIMSK1 |= 1<<TOIE1;
}
uint8_t windings_on_layer = windings % 25;
if(windings_on_layer == 0 && steps == 0){
trans_state = 1;
ICR1 = ICR5/TRANS_ROT_FACTOR;
OCR1A = ICR1/2;
set_Output(MOTOR_TRANS_DIR, TOGGLE);
printf("toggle at pos: %ld\n", spule_trans_pos);
printf("speed %d\n", ICR1);
}
if(windings_on_layer == 1 && steps == 0){
trans_state = 2;
printf("nachlauf aufbauen\n");
TCCR1B &= ~(_BV(CS11));
}
if(windings_on_layer == 3 && steps == 0){
trans_state = 3;
TCCR1B |= _BV(CS11);
printf("done\n");
printf("speed %d\n", ICR1);
}
if(windings_on_layer == 21 && steps == 0){
trans_state = 4;
ICR1 = 0.5*(ICR5/TRANS_ROT_FACTOR);
OCR1A = ICR1/2;
printf("nachlauf abbauen\n");
printf("speed %d\n", ICR1);
}
//;PORTH |= (1<<5);
} }

View File

@@ -1,7 +1,13 @@
#ifndef _SPULE_H_ #ifndef _SPULE_H_
#define _SPULE_H_ #define _SPULE_H_
#include <stdint.h>
void timer1_init(void);
void timer5_init(void); void timer5_init(void);
void do_spule(void); void do_spule(void);
extern volatile uint16_t windings;
extern int32_t spule_trans_pos;
#endif #endif

112
taenzer.c
View File

@@ -3,48 +3,118 @@
#include "taenzer.h" #include "taenzer.h"
#include "avrIOhelper/io-helper.h" #include "avrIOhelper/io-helper.h"
#include "kraftsensor.h" #include "kraftsensor.h"
#include "notaus.h"
#include "pid_controller.h"
#include "common.h"
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
taenzer_state_t taenzer_state;
#define TAENZER_KRAFT_SETPOINT 12000 #define TAENZER_KRAFT_SETPOINT 12000
#define TAENZER_KRAFT_HYST 2000 #define TAENZER_KRAFT_HYST 500
taenzer_state_t taenzer_state;
PID_VARS_INIT(regler);
taenzer_state_t taenzer_state = {
.homed = 0,
.pos = 0,
.force_setpoint = TAENZER_KRAFT_SETPOINT,
.active = 0
};
double pid(PID_vars *vars, double current_err) {
/* current_error = setpoint - current_process_variable */
vars->_integral_sum += current_err*(vars->_dt);
double output = (vars->Kp)*current_err \
+ (vars->Ki)*(vars->_integral_sum) \
+ (vars->Kd)*((current_err-(vars->_prev_err)) \
/(vars->_dt));
vars->_prev_err = current_err;
/* limit output within output_min and output_max */
if (output>(vars->output_max))
output = vars->output_max;
else if (output<(vars->output_min))
output = vars->output_min;
return output;
}
extern void send_settings(void);
void do_taenzer(){ void do_taenzer(){
/* Homing */ /* Homing */
if(!taenzer_state.homed){
set_Output(MOTOR_TAENZER_DIR, 1); // direction: up
TCCR4B |= _BV(CS41); //TURN ON
}
if(read_Input(IN_TAENZER_HOME, LEVEL)){ if(read_Input(IN_TAENZER_HOME, LEVEL)){
TCCR4B &= ~_BV(CS41); //TURN OFF TCCR4B &= ~_BV(CS41); //TURN OFF
taenzer_state.homed = 1; taenzer_state.homed = 1;
taenzer_state.pos = 0; taenzer_state.pos = 0;
} }
if(!taenzer_state.homed && notaus_state == POWER_ON){
ICR4 = 30;
OCR4A = 15;
set_Output(MOTOR_TAENZER_DIR, 1); // direction: up
TCCR4B |= _BV(CS41); //TURN ON
}
if (read_Input(BTN_KRAFT_PLUS, RISING)) {
taenzer_state.force_setpoint += 1000;
#if PLC_MQTT_ENABLED
send_settings();
#endif
if(taenzer_state.homed == 1 && read_Input(BTN_KRAFT_MINUS, LEVEL))
{
kraftsensor_zero_offset = -(kraftsensor_value-kraftsensor_zero_offset);
}
}
if (read_Input(BTN_KRAFT_MINUS, RISING)) {
taenzer_state.force_setpoint -= 1000;
#if PLC_MQTT_ENABLED
send_settings();
#endif
if(taenzer_state.homed == 1 && read_Input(BTN_KRAFT_PLUS, LEVEL))
{
kraftsensor_zero_offset = -(kraftsensor_value-kraftsensor_zero_offset);
}
}
if (read_Input(BTN_TAENZER_START, RISING)) {
taenzer_state.active = 1;
}
/* Force regualtion */ /* Force regualtion */
if(kraftsensor_valid && taenzer_state.homed){ if(kraftsensor_valid && taenzer_state.active && taenzer_state.homed && taenzer_state.pos >= 0){
int16_t err = abs(kraftsensor_value - TAENZER_KRAFT_SETPOINT); int32_t err = (kraftsensor_value - taenzer_state.force_setpoint);
if(err > 8000) double pid_out = pid(&regler, err);
err=8000; int32_t out = (int32_t)pid_out;
ICR4 = 400000/err; ICR4 = 400000/abs(out);
OCR4A = ICR4/2; OCR4A = ICR4/2;
if(kraftsensor_value < TAENZER_KRAFT_SETPOINT - (TAENZER_KRAFT_HYST/2)){ if(kraftsensor_valid && notaus_state == POWER_ON){
set_Output(MOTOR_TAENZER_DIR, 0); // direction: down if(out < -TAENZER_KRAFT_HYST/2 && taenzer_state.pos < 970000UL){
TCCR4B |= _BV(CS41); //TURN ON set_Output(MOTOR_TAENZER_DIR, 0); // direction: down
} TCCR4B |= _BV(CS41); //TURN ON
else if(kraftsensor_value > TAENZER_KRAFT_SETPOINT + (TAENZER_KRAFT_HYST/2)){ }
set_Output(MOTOR_TAENZER_DIR, 1); // direction: up else if(out > TAENZER_KRAFT_HYST/2 && taenzer_state.pos > 0){
TCCR4B |= _BV(CS41); //TURN ON set_Output(MOTOR_TAENZER_DIR, 1); // direction: up
TCCR4B |= _BV(CS41); //TURN ON
}
else{
TCCR4B &= ~_BV(CS41); //TURN OFF
}
} }
else else
TCCR4B &= ~_BV(CS41); //TURN OFF TCCR4B &= ~_BV(CS41); //TURN OFF
} }
//else
// TCCR4B &= ~_BV(CS41); //TURN OFF
} }
void timer4_init() void timer4_init()
@@ -55,8 +125,8 @@ void timer4_init()
TIMSK4 |= 1<<TOIE4; TIMSK4 |= 1<<TOIE4;
// TIMSK4 |= 1<<OCIE4A; // TIMSK4 |= 1<<OCIE4A;
ICR4 = 50; ICR4 = 30;
OCR4A = 25; OCR4A = 15;
DDRH |= 1 << 3; DDRH |= 1 << 3;
} }

View File

@@ -3,11 +3,12 @@
#include <stdint.h> #include <stdint.h>
typedef struct { typedef volatile struct {
uint8_t homed; uint8_t homed;
uint32_t pos; uint32_t pos;
int16_t force_setpoint;
uint8_t active;
} taenzer_state_t; } taenzer_state_t;
extern taenzer_state_t taenzer_state; extern taenzer_state_t taenzer_state;
void do_taenzer(void); void do_taenzer(void);