initial commit
This commit is contained in:
105
Arduino_PLC/Arduino_PLC.ino
Normal file
105
Arduino_PLC/Arduino_PLC.ino
Normal file
@@ -0,0 +1,105 @@
|
||||
/*
|
||||
Name: B_FVI_AGV.ino
|
||||
Created: 2022-11-16 오전 13:32:00
|
||||
Author: KIMCHK
|
||||
*/
|
||||
|
||||
#include "motor.h"
|
||||
#include "IO.h"
|
||||
#include "HmiClass.h"
|
||||
#include "UtilClass.h"
|
||||
#include "VarClass.h"
|
||||
#include "VarClass.h"
|
||||
#include <SPI.h>
|
||||
|
||||
int debugportvalue = 0;
|
||||
String version = "22.11.16.1716";
|
||||
String debugmessage = "";
|
||||
void(*resetFunc)(void) = 0;
|
||||
unsigned long timesyncvalue = 0;
|
||||
unsigned long startTime = 0;
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(57600); //디버그 및 업로드 포트
|
||||
Serial1.begin(57600); //통신 포트
|
||||
|
||||
/*while (!Serial)
|
||||
true;
|
||||
|
||||
while (!Serial1)
|
||||
true;*/
|
||||
|
||||
pinMode(13,OUTPUT);
|
||||
|
||||
var.eeprom_load(); //플래그 우선 복원
|
||||
|
||||
io.Setup();
|
||||
hmi.Setup(); //HMI 초기화
|
||||
var.Setup();
|
||||
mot.Setup();
|
||||
|
||||
hmi.SendMessage(F("##:SETUP:OK"),false);
|
||||
hmi.SendMessage(String("##:VERSION:") + String(version), false);
|
||||
|
||||
//TCCR1B = TCCR1B & B11111000 | B00000001; // set timer 1 divisor to 1 for PWM frequency of 31372.55 Hz
|
||||
TCCR1B = TCCR1B & B11111000 | B00000010; // set timer 1 divisor to 8 for PWM frequency of 3921.16 Hz
|
||||
TCNT1 = 0x0000;
|
||||
//TCCR1B = TCCR1B & B11111000 | B00000011; // set timer 1 divisor to 64 for PWM frequency of 490.20 Hz
|
||||
|
||||
PrintDebugCommand();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
io.Update(); //DIO 상태 학인;
|
||||
var.Update(); //가변변수 업데이트
|
||||
mot.Update(); // 모터제어
|
||||
hmi.Update(); //HMI Events
|
||||
|
||||
//초기화
|
||||
if (var.runReset)
|
||||
{
|
||||
Serial.println("** RESET **");
|
||||
var.eeprom_incResetCount();
|
||||
var.runReset = false;
|
||||
resetFunc();
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
//경과시간
|
||||
unsigned long runtime = millis() - startTime;
|
||||
if (runtime > 60000) var.runtime = 60000;
|
||||
else var.runtime = (uint16_t)runtime;
|
||||
startTime = millis();
|
||||
|
||||
if(startTime % 500 == 0)
|
||||
{
|
||||
if(digitalRead(13)==HIGH)
|
||||
digitalWrite(13,LOW);
|
||||
else
|
||||
digitalWrite(13,HIGH);
|
||||
}
|
||||
|
||||
}
|
||||
void UpdateTime()
|
||||
{
|
||||
//시간정보를 조회한다. 190319
|
||||
timesyncvalue = millis();
|
||||
}
|
||||
void PrintDebugCommand()
|
||||
{
|
||||
String data = "";
|
||||
data += String("====================================\n");
|
||||
data += String("## AGV Z-Motor Controller\n");
|
||||
data += String("## Version "+ version + "\n" );
|
||||
data += String("## Created by ATK4-EET-1P\n");
|
||||
data += String("====================================\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String(">> ZUP (z-axis move up)\n");
|
||||
data += String("====================================\n");
|
||||
Serial.println(data);
|
||||
}
|
||||
120
Arduino_PLC/FontList.txt
Normal file
120
Arduino_PLC/FontList.txt
Normal file
@@ -0,0 +1,120 @@
|
||||
//16
|
||||
<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ġ<EFBFBD>˻<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ظ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ϰ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>±ػ<EFBFBD><EFBFBD>뿬<EFBFBD>Ἥ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ӱ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ӵ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ȣ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ð<EFBFBD>Ŀ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ʒ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ѹ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ӵ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>к<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϸ<EFBFBD><EFBFBD>ʱ<EFBFBD>ȭ(#%).-:/><_<><5F><EFBFBD>¸<EFBFBD><C2B8><EFBFBD><EFBFBD>ͽý<CDBD><C3BD>ۼ<EFBFBD><DBBC><EFBFBD><EFBFBD>ڵ<EFBFBD><DAB5><EFBFBD><EFBFBD><EFBFBD>I/O<><4F><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD>ȭ01234456789SNOVRDCNSTLIMITHOMECHRGALIGNPAUSEMAGFMAGBXBEERFIDABCDEFTIME<4D><45><EFBFBD><EFBFBD>Ȩ<EFBFBD><C8A8><EFBFBD><EFBFBD><EFBFBD>ڵ<EFBFBD><DAB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>̵<EFBFBD><CCB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ITEMONTAKEABCDEFGHIJKLMNOPQRSTUVWXYZv<5A><76><EFBFBD><EFBFBD><EFBFBD>Ӱ谪<D3B0>Ѱ谨<D1B0><E8B0A8>ms=
|
||||
//80
|
||||
QCA0123456789H<EFBFBD>ڵ<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
//40
|
||||
<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ư<EFBFBD><EFBFBD><EFBFBD>پ<EFBFBD>ȣQCAzZ<EFBFBD><EFBFBD>%<25><><EFBFBD>ø<EFBFBD><C3B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>-=_MHPACKINGQCQARFIDXBEE<45><45><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ġã<C4A1><C3A3><EFBFBD>߿Ϸ<DFBF><CFB7>Ǿ<EFBFBD><C7BE><EFBFBD><EFBFBD>ϴ<EFBFBD><CFB4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʿ<EFBFBD><CABF>մϴ<D5B4><CFB4><EFBFBD><EFBFBD>ۻ<EFBFBD><DBBB><EFBFBD><EFBFBD>ڼ<EFBFBD><DABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʿ<EFBFBD><CABF><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڷ¼<DAB7><C2BC><EFBFBD><EFBFBD>յ<EFBFBD><D5B5><EFBFBD><EFBFBD>Ų<EFBFBD><C5B2><EFBFBD>()[#]<5D><><EFBFBD><EFBFBD><EFBFBD>յ<EFBFBD><D5B5>¿<EFBFBD>CW0123456789.vLOADING<4E><47><EFBFBD><EFBFBD>Ŀ<EFBFBD><C4BF><EFBFBD><EFBFBD><EFBFBD>÷<EFBFBD><C3B7><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ּ<EFBFBD><D6BC><EFBFBD><EFBFBD><EFBFBD>ġã<C4A1><C3A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ġ<EFBFBD>˻<EFBFBD><CBBB>غ<EFBFBD><D8BA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˼<EFBFBD><CBBC><EFBFBD><EFBFBD><EFBFBD><EFBFBD>̵<EFBFBD><CCB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>̵<EFBFBD><CCB5><EFBFBD>Ȩ<EFBFBD><C8A8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
if(va0.val==0)
|
||||
{
|
||||
msg.txt="<22><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va3.val==0)
|
||||
{
|
||||
msg.txt="RFID <20><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va4.val==0)
|
||||
{
|
||||
msg.txt="XBEE <20><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va6.val==0)
|
||||
{
|
||||
msg.txt="<22>ڷ¼<DAB7><C2BC><EFBFBD>(<28><>) <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va7.val==0)
|
||||
{
|
||||
msg.txt="<22>ڷ¼<DAB7><C2BC><EFBFBD>(<28><>) <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va8.val>0)
|
||||
{
|
||||
msg.txt="<22><><EFBFBD><EFBFBD> <20><>"
|
||||
tbco.val=63846
|
||||
}else if(va1.val>0)
|
||||
{
|
||||
msg.txt="<22><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va5.val>0)
|
||||
{
|
||||
msg.txt="(Z<><5A>) <20><><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD>"
|
||||
tbco.val=63846
|
||||
}else if(va2.val==0)
|
||||
{
|
||||
tbco.val=64520
|
||||
if(varmc.val==0)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD>"
|
||||
}else if(varmc.val==1)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD>"
|
||||
}else if(varmc.val==2)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>"
|
||||
}else if(varmc.val==3)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD>"
|
||||
}else if(varmc.val==4)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD>"
|
||||
}else if(varmc.val==5)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20>̵<EFBFBD>(Ȩ)"
|
||||
}else if(varmc.val==6)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20>̵<EFBFBD>(<28><><EFBFBD><EFBFBD>)"
|
||||
}else if(varmc.val==16)
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
}else
|
||||
{
|
||||
msg.txt="(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>) <20>˼<EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
}
|
||||
}else
|
||||
{
|
||||
//autorun mode : parse message
|
||||
tbco.val=1048
|
||||
if(varmc.val==0)
|
||||
{
|
||||
msg.txt="[#1] Ŀ<><C4BF><EFBFBD><EFBFBD> <20>÷<EFBFBD> <20>ּ<EFBFBD><D6BC><EFBFBD>" //mcodevalue
|
||||
}else if(varmc.val==1)
|
||||
{
|
||||
msg.txt="[#2] <20>̵<EFBFBD><CCB5><EFBFBD>(<28><><EFBFBD><EFBFBD>)" //mcodevalue
|
||||
}else if(varmc.val==2)
|
||||
{
|
||||
msg.txt="[#3] <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20>ʿ<EFBFBD><CABF>մϴ<D5B4>" //mcodevalue
|
||||
}else if(varmc.val==3)
|
||||
{
|
||||
msg.txt="[#4] <20>̵<EFBFBD><CCB5><EFBFBD>(Ȩ)" //mcodevalue
|
||||
}else if(varmc.val==4)
|
||||
{
|
||||
msg.txt="[#5] <20>̵<EFBFBD> <20><>(<28><><EFBFBD><EFBFBD>)" //mcodevalue
|
||||
}else if(varmc.val==5)
|
||||
{
|
||||
msg.txt="[#6] <20>̵<EFBFBD> <20><>(<28><><EFBFBD><EFBFBD>)" //mcodevalue
|
||||
}else if(varmc.val==6)
|
||||
{
|
||||
msg.txt="[#7] <20><><EFBFBD><EFBFBD>" //mcodevalue
|
||||
}else if(varmc.val==7)
|
||||
{
|
||||
msg.txt="[#8] Ŀ<><C4BF><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD> <20>ּ<EFBFBD><D6BC><EFBFBD>" //mcodevalue
|
||||
}else if(varmc.val==8)
|
||||
{
|
||||
msg.txt="[#9] <20><><EFBFBD><EFBFBD> <20><>ġ ã<><C3A3> <20><>" //mcodevalue
|
||||
}else if(varmc.val==9)
|
||||
{
|
||||
msg.txt="[#10] <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ġ ã<><C3A3> <20><>" //mcodevalue
|
||||
}else if(varmc.val==10)
|
||||
{
|
||||
msg.txt="[#11] <20><><EFBFBD><EFBFBD> <20>غ<EFBFBD>" //mcodevalue
|
||||
}else if(varmc.val==11)
|
||||
{
|
||||
msg.txt="[#12] <20><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>" //mcodevalue
|
||||
}else
|
||||
{
|
||||
msg.txt="[#99] <20>˼<EFBFBD> <20><><EFBFBD><EFBFBD>"
|
||||
}
|
||||
}
|
||||
if(tbmsg.txt!=msg.txt)
|
||||
{
|
||||
tbmsg.txt=msg.txt
|
||||
tbmsg.bco=tbco.val
|
||||
}
|
||||
569
Arduino_PLC/HmiClass.cpp
Normal file
569
Arduino_PLC/HmiClass.cpp
Normal file
@@ -0,0 +1,569 @@
|
||||
#include "IO.h"
|
||||
#include "VarClass.h"
|
||||
#include "HmiClass.h"
|
||||
#include "UtilClass.h"
|
||||
#include "motor.h"
|
||||
#include "arduino.h"
|
||||
|
||||
unsigned long errtime = 0;
|
||||
unsigned long eruntime = 0;
|
||||
|
||||
void HmiClass::Setup()
|
||||
{
|
||||
hmi.SendMessage("##:HMI:SETUP", false);
|
||||
updatetime = millis();
|
||||
ClearTempBuffer0();
|
||||
ClearTempBuffer1();
|
||||
}
|
||||
|
||||
void HmiClass::Update()
|
||||
{
|
||||
//데이터는 일정 주기로 전송한다.
|
||||
unsigned long runtime = millis() - updatetime;
|
||||
uint8_t loopterm = var._eep_iosendinterval;
|
||||
|
||||
loopterm = 500;
|
||||
|
||||
//설정 중에는 통신속도를 초당 10번으로 고정한다
|
||||
if (var.getFlag(FLAG_SETUP) == true) loopterm = 100;
|
||||
if (runtime > loopterm)
|
||||
{
|
||||
//IO상태전송
|
||||
SendIOStatus();
|
||||
|
||||
//설정모드에서는 계속 전송 한다
|
||||
if (var.getFlag(FLAG_SETUP) == true)
|
||||
{
|
||||
//EEP정보 전송
|
||||
SendSetupInfo();
|
||||
}
|
||||
updatetime = millis();
|
||||
}
|
||||
|
||||
//입력값 감지 190319
|
||||
CheckReceiveS0();
|
||||
CheckReceiveS1();
|
||||
}
|
||||
|
||||
void HmiClass::SendIOStatus()
|
||||
{
|
||||
//전송데이터처리
|
||||
byte payload[29]; //IO4바이트(uint32), A0~A3 A는 각 2바이트(uint16)
|
||||
byte payidx = 0;
|
||||
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = 10; //데이터 길이
|
||||
payload[payidx++] = 'I'; //49=I(IO)
|
||||
payload[payidx++] = (byte)(var.IOData >> 0); //INPUT(16)
|
||||
payload[payidx++] = (byte)(var.IOData >> 8); //OUTPUT(16)
|
||||
payload[payidx++] = (byte)(var.IOData >> 16);
|
||||
payload[payidx++] = (byte)(var.IOData >> 24);
|
||||
|
||||
uint32_t flagValue = var.getFlagValue();
|
||||
payload[payidx++] = (byte)(flagValue >> 0); //FLAG (0~31)
|
||||
payload[payidx++] = (byte)(flagValue >> 8);
|
||||
payload[payidx++] = (byte)(flagValue >> 16);
|
||||
payload[payidx++] = (byte)(flagValue >> 24);
|
||||
|
||||
//쓰레드진행시간
|
||||
payload[payidx++] = (byte)var.runtime;
|
||||
|
||||
//checksum
|
||||
byte checksum = 0;
|
||||
for (int i = 3; i < payidx; i++)
|
||||
checksum = checksum ^ payload[i];
|
||||
|
||||
payload[payidx++] = checksum;
|
||||
payload[payidx++] = 0x0D;
|
||||
payload[payidx++] = 0x0A;
|
||||
|
||||
//Serial.print("Send Payload len=");
|
||||
//Serial.println(payidx);
|
||||
|
||||
hmiSerial.write(payload, payidx);
|
||||
hmiSerial.flush();
|
||||
|
||||
//20190325 - 1번포트로 미러링
|
||||
//dbgSerial.write(payload, sizeof(payload));
|
||||
//dbgSerial.flush();
|
||||
}
|
||||
|
||||
void HmiClass::SendSetupInfo()
|
||||
{
|
||||
//전송데이터처리
|
||||
byte payload[19]; //IO4바이트(uint32), A0~A3 A는 각 2바이트(uint16)
|
||||
byte payidx = 0;
|
||||
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = 5; //데이터 길이
|
||||
payload[payidx++] = 'S'; //49=I(IO),T=TEXT,S=SETUP
|
||||
payload[payidx++] = var._eep_iosendinterval;
|
||||
payload[payidx++] = var._eep_resetcount;
|
||||
payload[payidx++] = var._eep_pindir_iH;
|
||||
payload[payidx++] = var._eep_pindir_iL;
|
||||
|
||||
//checksum
|
||||
byte checksum = 0;
|
||||
for (int i = 3; i < payidx; i++)
|
||||
checksum = checksum ^ payload[i];
|
||||
|
||||
payload[payidx++] = checksum;
|
||||
payload[payidx++] = 0x0D;
|
||||
payload[payidx++] = 0x0A;
|
||||
|
||||
//Serial.print("Send Payload len=");
|
||||
//Serial.println(sizeof(payload));
|
||||
|
||||
hmiSerial.write(payload, sizeof(payload));
|
||||
hmiSerial.flush();
|
||||
|
||||
//20190325 - 1번포트로 미러링
|
||||
//dbgSerial.write(payload, sizeof(payload));
|
||||
//dbgSerial.flush();
|
||||
}
|
||||
|
||||
void HmiClass::CheckReceiveS0()
|
||||
{
|
||||
//수신데이터가 있는경우에만 처리함
|
||||
//bool newdata = hmiSerial.available() > 0;
|
||||
//if (newdata) sprint(F("HMI Received Data ["));
|
||||
while (hmiSerial.available() > 0) {
|
||||
incomingByte0 = (char)(hmiSerial.read());
|
||||
|
||||
if (STX1S0 == false)
|
||||
{
|
||||
if (incomingByte0 != '@')
|
||||
{
|
||||
STX2S0 = false;
|
||||
ETX1S0 = false;
|
||||
SendMessage(F("ERROR:STX1"), true);
|
||||
continue;
|
||||
}
|
||||
else
|
||||
{
|
||||
STX1S0 = true;
|
||||
ClearTempBuffer0();
|
||||
Tempbuffer1[bufferIndex0++] = incomingByte0; //Tempbuffer1 += incomingByte;
|
||||
}
|
||||
}
|
||||
else if (STX2S0 == false)
|
||||
{
|
||||
if (bufferIndex0 != 1 || bufferIndex0 < 1 || Tempbuffer1[0] != '@' || incomingByte0 != '@')
|
||||
{
|
||||
STX1S0 = false;
|
||||
ETX1S0 = false;
|
||||
SendMessage(F("ERROR:STX2"), true);
|
||||
continue;
|
||||
}
|
||||
else
|
||||
{
|
||||
STX2S0 = true;
|
||||
Tempbuffer1[bufferIndex0++] = incomingByte0; //Tempbuffer1 += incomingByte;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
Tempbuffer1[bufferIndex0++] = incomingByte0; //Tempbuffer1 += incomingByte;
|
||||
|
||||
//여기서부터는무조건 누적한다.
|
||||
if (bufferIndex0 == 3)
|
||||
{
|
||||
if (Tempbuffer1[0] != 0x40 || Tempbuffer1[1] != '@')
|
||||
{
|
||||
STX1S0 = false;
|
||||
STX2S0 = false;
|
||||
ETX1S0 = false;
|
||||
|
||||
bufferIndex0 = 0; // = "";
|
||||
}
|
||||
else LEN1 = incomingByte0; //데이터 길이가온다
|
||||
}
|
||||
else if (bufferIndex0 == LEN1 + 2 + 1 + 1) //체크섬이 왔다
|
||||
{
|
||||
CHK1 = incomingByte0;
|
||||
}
|
||||
else if (bufferIndex0 == LEN1 + 2 + 1 + 1 + 1) //ETX1
|
||||
{
|
||||
if (incomingByte0 != 0x0D)
|
||||
{
|
||||
//ETX가 와야하는데 다른데이터가 왔다
|
||||
STX1S0 = false;
|
||||
STX2S0 = false;
|
||||
ETX1S0 = false;
|
||||
bufferIndex0 = 0;//
|
||||
SendMessage(F("ERROR:STX3"), true);
|
||||
}
|
||||
}
|
||||
else if (bufferIndex0 == LEN1 + 2 + 1 + 1 + 1 + 1)
|
||||
{
|
||||
//전체길이를 만족햇다.
|
||||
if (incomingByte0 != 0x0A)
|
||||
{
|
||||
//ETX가 와야하는데 다른데이터가 왔다
|
||||
STX1S0 = false;
|
||||
STX2S0 = false;
|
||||
ETX1S0 = false;
|
||||
//Console.WriteLine("에러 모두 파기");
|
||||
bufferIndex0 = 0;// == "";//.Clear();
|
||||
SendMessage(F("ERROR:STX4"), true);
|
||||
}
|
||||
else
|
||||
{
|
||||
STX1S0 = false;
|
||||
STX2S0 = false;
|
||||
ETX1S0 = false;
|
||||
|
||||
//임시버퍼의 데이터를 수신데이터 변수에 넣는다
|
||||
//memcpy(buffer.c_str(), Tempbuffer1.c_str(), sizeof(Tempbuffer1));
|
||||
//Tempbuffer1.toCharArray()
|
||||
//buffer = Tempbuffer1;
|
||||
Parser(bufferIndex0);
|
||||
bufferIndex0 = 0;
|
||||
//Tempbuffer1[0] = 0; //첫비트에 nullstring 을 넣는다
|
||||
//var.runCommand( parser(buffer1, addMsg1, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
////stx ,etx 는 hex 처리하고 번호와 값을 ascii처리함
|
||||
//if (incomingByte == 0x02) buffer = "";
|
||||
//else if (incomingByte == 0x03)
|
||||
//{
|
||||
// //ETX값이나 전체 길이가 4가아니라면 추가해야함
|
||||
// uint8_t butNo = (uint8_t)(buffer.substring(0, 3).toInt());
|
||||
// uint8_t butValue = (uint8_t)(buffer.substring(3, 4).toInt());
|
||||
// //remote 명령과 공유하기 위해서 util로 이동
|
||||
// var.runCommand((eCommand)butNo, butValue,0); //NewMsgEvent(butNo, butValue);
|
||||
// break;
|
||||
//}
|
||||
//else{
|
||||
// buffer += (char)incomingByte; //문자를 누적시킨다.
|
||||
// if (buffer.length() > 10) {
|
||||
// sprintln(F("HMI buffer Over error"));
|
||||
// buffer = "";
|
||||
// }
|
||||
//}
|
||||
}
|
||||
//if (newdata) sprintln("]");
|
||||
}
|
||||
|
||||
void HmiClass::CheckReceiveS1()
|
||||
{
|
||||
//수신데이터가 있는경우에만 처리함
|
||||
//bool newdata = dbgSerial.available() > 0;
|
||||
//if (newdata) sprint(F("HMI Received Data ["));
|
||||
while (dbgSerial.available() > 0) {
|
||||
incomingByte1 = (char)(dbgSerial.read());
|
||||
|
||||
if(incomingByte1 == 0x0A) //if newline
|
||||
{
|
||||
String cmd = "";
|
||||
for(int i = 0 ; i < bufferIndex1;i++)
|
||||
{
|
||||
cmd += String((char)Tempbuffer1[i]);
|
||||
}
|
||||
|
||||
if(cmd.equals("UP")||cmd.equals("up"))
|
||||
{
|
||||
Serial.println("User command : z-up");
|
||||
mot.SetZRun(ZRUN_UP);
|
||||
}
|
||||
else if(cmd.equals("DN")||cmd.equals("dn"))
|
||||
{
|
||||
Serial.println("User command : z-down");
|
||||
mot.SetZRun(ZRUN_DN);
|
||||
}
|
||||
else if(cmd.equals("STOP")||cmd.equals("stop"))
|
||||
{
|
||||
Serial.println("User command : z-stop");
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
else{
|
||||
Serial.print("Unknown Command : ");
|
||||
Serial.println(cmd);
|
||||
}
|
||||
|
||||
bufferIndex1 = 0;
|
||||
}
|
||||
else if(bufferIndex1 > 99)
|
||||
{
|
||||
Serial.println(F("recv1 length error(>99"));
|
||||
bufferIndex1 = 0;
|
||||
}
|
||||
else {
|
||||
Tempbuffer1[bufferIndex1++] = incomingByte1; //Tempbuffer1 += incomingByte;
|
||||
}
|
||||
}
|
||||
//if (newdata) sprintln("]");
|
||||
}
|
||||
/*
|
||||
void HmiClass::CheckReceiveS1_Backup_221117()
|
||||
{
|
||||
//수신데이터가 있는경우에만 처리함
|
||||
bool newdata = dbgSerial.available() > 0;
|
||||
//if (newdata) sprint(F("HMI Received Data ["));
|
||||
while (dbgSerial.available() > 0) {
|
||||
incomingByte1 = (char)(dbgSerial.read());
|
||||
|
||||
if (STX1S1 == false)
|
||||
{
|
||||
if (incomingByte1 != '@')
|
||||
{
|
||||
STX2S1 = false;
|
||||
ETX1S1 = false;
|
||||
SendMessage(F("ERROR:STX1"), true);
|
||||
continue;
|
||||
}
|
||||
else
|
||||
{
|
||||
STX1S1 = true;
|
||||
ClearTempBuffer1();
|
||||
Tempbuffer1[bufferIndex1++] = incomingByte1; //Tempbuffer1 += incomingByte;
|
||||
}
|
||||
}
|
||||
else if (STX2S1 == false)
|
||||
{
|
||||
if (bufferIndex1 != 1 || bufferIndex1 < 1 || Tempbuffer1[0] != '@' || incomingByte1 != '@')
|
||||
{
|
||||
STX1S1 = false;
|
||||
ETX1S1 = false;
|
||||
SendMessage(F("ERROR:STX2"), true);
|
||||
continue;
|
||||
}
|
||||
else
|
||||
{
|
||||
STX2S1 = true;
|
||||
Tempbuffer1[bufferIndex1++] = incomingByte1; //Tempbuffer1 += incomingByte;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
Tempbuffer1[bufferIndex1++] = incomingByte1; //Tempbuffer1 += incomingByte;
|
||||
|
||||
//여기서부터는무조건 누적한다.
|
||||
if (bufferIndex1 == 3)
|
||||
{
|
||||
if (Tempbuffer1[0] != 0x40 || Tempbuffer1[1] != '@')
|
||||
{
|
||||
STX1S1 = false;
|
||||
STX2S1 = false;
|
||||
ETX1S1 = false;
|
||||
|
||||
bufferIndex1 = 0; // = "";
|
||||
}
|
||||
else LEN1 = incomingByte1; //데이터 길이가온다
|
||||
}
|
||||
else if (bufferIndex1 == LEN1 + 2 + 1 + 1) //체크섬이 왔다
|
||||
{
|
||||
CHK1 = incomingByte1;
|
||||
}
|
||||
else if (bufferIndex1 == LEN1 + 2 + 1 + 1 + 1) //ETX1
|
||||
{
|
||||
if (incomingByte1 != 0x0D)
|
||||
{
|
||||
//ETX가 와야하는데 다른데이터가 왔다
|
||||
STX1S1 = false;
|
||||
STX2S1 = false;
|
||||
ETX1S1 = false;
|
||||
bufferIndex1 = 0;//
|
||||
SendMessage(F("ERROR:STX3"), true);
|
||||
}
|
||||
}
|
||||
else if (bufferIndex1 == LEN1 + 2 + 1 + 1 + 1 + 1)
|
||||
{
|
||||
//전체길이를 만족햇다.
|
||||
if (incomingByte1 != 0x0A)
|
||||
{
|
||||
//ETX가 와야하는데 다른데이터가 왔다
|
||||
STX1S1 = false;
|
||||
STX2S1 = false;
|
||||
ETX1S1 = false;
|
||||
//Console.WriteLine("에러 모두 파기");
|
||||
bufferIndex1 = 0;// == "";//.Clear();
|
||||
SendMessage(F("ERROR:STX4"), true);
|
||||
}
|
||||
else
|
||||
{
|
||||
STX1S1 = false;
|
||||
STX2S1 = false;
|
||||
ETX1S1 = false;
|
||||
|
||||
//임시버퍼의 데이터를 수신데이터 변수에 넣는다
|
||||
//memcpy(buffer.c_str(), Tempbuffer1.c_str(), sizeof(Tempbuffer1));
|
||||
//Tempbuffer1.toCharArray()
|
||||
//buffer = Tempbuffer1;
|
||||
Parser(bufferIndex1);
|
||||
bufferIndex1 = 0;
|
||||
//Tempbuffer1[0] = 0; //첫비트에 nullstring 을 넣는다
|
||||
//var.runCommand( parser(buffer1, addMsg1, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
////stx ,etx 는 hex 처리하고 번호와 값을 ascii처리함
|
||||
//if (incomingByte == 0x02) buffer = "";
|
||||
//else if (incomingByte == 0x03)
|
||||
//{
|
||||
// //ETX값이나 전체 길이가 4가아니라면 추가해야함
|
||||
// uint8_t butNo = (uint8_t)(buffer.substring(0, 3).toInt());
|
||||
// uint8_t butValue = (uint8_t)(buffer.substring(3, 4).toInt());
|
||||
// //remote 명령과 공유하기 위해서 util로 이동
|
||||
// var.runCommand((eCommand)butNo, butValue,0); //NewMsgEvent(butNo, butValue);
|
||||
// break;
|
||||
//}
|
||||
//else{
|
||||
// buffer += (char)incomingByte; //문자를 누적시킨다.
|
||||
// if (buffer.length() > 10) {
|
||||
// sprintln(F("HMI buffer Over error"));
|
||||
// buffer = "";
|
||||
// }
|
||||
//}
|
||||
}
|
||||
//if (newdata) sprintln("]");
|
||||
}
|
||||
*/
|
||||
|
||||
void HmiClass::Parser(byte bufferIndex)
|
||||
{
|
||||
Serial.println("Remote Command Parse");
|
||||
|
||||
//데이터를 분석해야 함
|
||||
if (Tempbuffer1[0] == '@' && Tempbuffer1[1] == '@' &&
|
||||
Tempbuffer1[bufferIndex - 2] == 0x0D && Tempbuffer1[bufferIndex - 1] == 0x0A)
|
||||
{
|
||||
byte len = Tempbuffer1[2];
|
||||
byte chk = Tempbuffer1[len + 3];
|
||||
if (bufferIndex != len + 6)
|
||||
{
|
||||
String msg = ("===>Frame length error len=");
|
||||
msg += String(bufferIndex);
|
||||
msg += (",receive=");
|
||||
msg += String(len + 6);
|
||||
SendMessage(msg, true);
|
||||
}
|
||||
else {
|
||||
//체크섬확인
|
||||
byte cs = 0;
|
||||
for (int i = 3; i < (3 + len); i++)
|
||||
cs = cs ^ Tempbuffer1[i];
|
||||
if (chk != cs)
|
||||
{
|
||||
String msg = ("===>checksum error calc=");
|
||||
msg.concat( String(cs));
|
||||
msg.concat("receive=");
|
||||
msg.concat(String(chk));
|
||||
SendMessage(msg, true);
|
||||
}
|
||||
else {
|
||||
//체크섬일치
|
||||
byte command = Tempbuffer1[3];
|
||||
byte param1 = Tempbuffer1[4];
|
||||
byte param2 = Tempbuffer1[5];
|
||||
var.runCommand((eCommand)command, param1, param2);
|
||||
}
|
||||
}
|
||||
}
|
||||
else {
|
||||
//프레임이 이상하다.
|
||||
//sprintln("===>Frame error stx, etx");
|
||||
SendMessage("==>Frame error no stx,etx", true);
|
||||
}
|
||||
}
|
||||
void HmiClass::ClearTempBuffer0()
|
||||
{
|
||||
LEN0 = 0;
|
||||
bufferIndex0 = 0;
|
||||
memcpy(Tempbuffer0, 0, sizeof(Tempbuffer0));
|
||||
}
|
||||
void HmiClass::ClearTempBuffer1()
|
||||
{
|
||||
LEN1 = 0;
|
||||
bufferIndex1 = 0;
|
||||
memcpy(Tempbuffer1, 0, sizeof(Tempbuffer1));
|
||||
}
|
||||
|
||||
void HmiClass::SendMessage(String message, bool isError)
|
||||
{
|
||||
if(message.equals(hmimessage))
|
||||
{
|
||||
//동일메세지가 왓다면 1초이내로 다시 전송하지 못하게 한다.
|
||||
if(hmimessagerepeat == 0 || hmimessagerepeat > millis())
|
||||
hmimessagerepeat = millis();
|
||||
|
||||
hmimessagetime = millis()-hmimessagerepeat;
|
||||
if(hmimessagetime < 999) return;
|
||||
|
||||
} else{
|
||||
hmimessagerepeat = millis();
|
||||
hmimessage = message;
|
||||
}
|
||||
// test = len 4 , totals 4+4=8
|
||||
// @ @ 6 T 0 t e s t chk \r \n
|
||||
byte totalLength = message.length() + 8;
|
||||
byte payload[100]; //IO4바이트(uint32), A0~A3 A는 각 2바이트(uint16)
|
||||
byte payidx = 0;
|
||||
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = message.length() + 2; //데이터 길이
|
||||
payload[payidx++] = 'T';
|
||||
payload[payidx++] = isError; //오류여부
|
||||
for (int i = 0; i < message.length(); i++)
|
||||
{
|
||||
payload[payidx++] = message[i];
|
||||
}
|
||||
|
||||
//checksum
|
||||
byte checksum = 0;
|
||||
for (int i = 3; i < (3 + message.length() + 2); i++)
|
||||
checksum = checksum ^ payload[i];
|
||||
|
||||
payload[payidx++] = checksum;
|
||||
payload[payidx++] = 0x0D;
|
||||
payload[payidx++] = 0x0A;
|
||||
|
||||
hmiSerial.write(payload, totalLength);
|
||||
hmiSerial.flush();
|
||||
|
||||
//20190325 - 1번포트로 미러링
|
||||
dbgSerial.println(message);
|
||||
//dbgSerial.write(message, message.length);
|
||||
//dbgSerial.flush();
|
||||
|
||||
}
|
||||
bool HmiClass::SendValue(char msg, uint32_t value)
|
||||
{
|
||||
byte totalLength = 11;
|
||||
byte payload[100]; //IO4바이트(uint32), A0~A3 A는 각 2바이트(uint16)
|
||||
byte payidx = 0;
|
||||
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = '@'; //@
|
||||
payload[payidx++] = 6; //데이터 길이
|
||||
payload[payidx++] = 'V';
|
||||
payload[payidx++] = msg; //값종류
|
||||
payload[payidx++] = (byte)(value >> 0);
|
||||
payload[payidx++] = (byte)(value >> 8);
|
||||
payload[payidx++] = (byte)(value >> 16);
|
||||
payload[payidx++] = (byte)(value >> 24);
|
||||
|
||||
//checksum
|
||||
byte checksum = 0;
|
||||
for (int i = 3; i < (3 + 4 + 2); i++)
|
||||
checksum = checksum ^ payload[i];
|
||||
|
||||
payload[payidx++] = checksum;
|
||||
payload[payidx++] = 0x0D;
|
||||
payload[payidx++] = 0x0C;
|
||||
|
||||
hmiSerial.write(payload, totalLength);
|
||||
hmiSerial.flush();
|
||||
|
||||
//20190325 - 1번포트로 미러링
|
||||
dbgSerial.write(payload, totalLength);
|
||||
dbgSerial.flush();
|
||||
}
|
||||
|
||||
HmiClass hmi;
|
||||
59
Arduino_PLC/HmiClass.h
Normal file
59
Arduino_PLC/HmiClass.h
Normal file
@@ -0,0 +1,59 @@
|
||||
#ifndef _HMICLASS_H_
|
||||
#define _HMICLASS_H_
|
||||
#include "arduino.h"
|
||||
|
||||
#define hmiSerial Serial1
|
||||
#define dbgSerial Serial
|
||||
|
||||
class HmiClass
|
||||
{
|
||||
public:
|
||||
|
||||
void Setup();
|
||||
void Update();
|
||||
void SendIOStatus();
|
||||
void SendSetupInfo();
|
||||
void SendMessage(String message, bool isError);
|
||||
bool SendValue(char msg, uint32_t value);
|
||||
bool showDebug = false;
|
||||
|
||||
private:
|
||||
|
||||
void ClearTempBuffer0();
|
||||
void ClearTempBuffer1();
|
||||
byte Tempbuffer0[100];
|
||||
byte Tempbuffer1[100];
|
||||
byte bufferIndex0 = 0;
|
||||
byte bufferIndex1 = 0;
|
||||
|
||||
unsigned long updatetime = 100; //데이터 전송 간격 측정을 위한 변수
|
||||
|
||||
void CheckReceiveS0(); //Serial0
|
||||
void CheckReceiveS1(); //Serial1
|
||||
|
||||
char incomingByte0; //수신버퍼에서 읽은 데이터를 임시 저장
|
||||
char incomingByte1; //수신버퍼에서 읽은 데이터를 임시 저장
|
||||
|
||||
//String buffer = ""; //수신버퍼 임시 저장 공간
|
||||
//String Tempbuffer1 = "";
|
||||
bool STX1S0 = false;
|
||||
bool STX2S0 = false;
|
||||
bool ETX1S0 = false;
|
||||
|
||||
bool STX1S1 = false;
|
||||
bool STX2S1 = false;
|
||||
bool ETX1S1 = false;
|
||||
|
||||
byte LEN1;
|
||||
byte CHK1;
|
||||
|
||||
byte LEN0;
|
||||
byte CHK0;
|
||||
|
||||
unsigned long hmimessagerepeat=0;
|
||||
unsigned long hmimessagetime =0;
|
||||
String hmimessage="";
|
||||
void Parser(byte bufferIndex);
|
||||
};
|
||||
extern HmiClass hmi;
|
||||
#endif
|
||||
386
Arduino_PLC/IO.cpp
Normal file
386
Arduino_PLC/IO.cpp
Normal file
@@ -0,0 +1,386 @@
|
||||
#include "IO.h"
|
||||
#include "VarClass.h"
|
||||
#include "motor.h"
|
||||
#include "HmiClass.h"
|
||||
#include "UtilClass.h"
|
||||
|
||||
void IoClass::Setup()
|
||||
{
|
||||
hmi.SendMessage("##:IO:SETUP", false);
|
||||
|
||||
byte DIPins[] = { 30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45 };
|
||||
byte DOPins[] = { 22,23,24,25,26,27,28,29 };
|
||||
|
||||
//입력포트 설정
|
||||
for (int i = 0; i < sizeof(DIPins); i++)
|
||||
pinMode(DIPins[i], INPUT);
|
||||
|
||||
//출력포트설정
|
||||
for (int i = 0; i < sizeof(DOPins); i++)
|
||||
pinMode(DOPins[i], OUTPUT);
|
||||
|
||||
//MAF 초기화
|
||||
for (int i = 0; i < MAF_SIZE; i++)
|
||||
{
|
||||
bufferF[i] = 0;
|
||||
bufferB[i] = 0;
|
||||
}
|
||||
|
||||
}
|
||||
void IoClass::Update()
|
||||
{
|
||||
|
||||
//Read DigitalInput
|
||||
|
||||
bool diValue[16]; int idx = 0;
|
||||
diValue[idx++] = digitalRead(PINI_EMG); //B접이다
|
||||
diValue[idx++] = digitalRead(PINI_BTN_1);
|
||||
diValue[idx++] = digitalRead(PINI_BTN_2);
|
||||
diValue[idx++] = digitalRead(PINI_BTN_3);
|
||||
diValue[idx++] = digitalRead(PINI_BTN_4);
|
||||
diValue[idx++] = digitalRead(PINI_OVERLOADL1);
|
||||
diValue[idx++] = digitalRead(PINI_OVERLOADL2);
|
||||
diValue[idx++] = digitalRead(PINI_OVERLOADR1);
|
||||
diValue[idx++] = digitalRead(PINI_OVERLOADR2);
|
||||
diValue[idx++] = digitalRead(PINI_EMPTY_38);
|
||||
diValue[idx++] = digitalRead(PINI_BTN_ZUP);
|
||||
diValue[idx++] = digitalRead(PINI_BTN_ZDN);
|
||||
diValue[idx++] = digitalRead(PINI_LIMIT_LU);
|
||||
diValue[idx++] = digitalRead(PINI_LIMIT_LD);
|
||||
diValue[idx++] = digitalRead(PINI_LIMIT_RU);
|
||||
diValue[idx++] = digitalRead(PINI_LIMIT_RD);
|
||||
diValue[idx++] = digitalRead(PINI_STOP);
|
||||
|
||||
|
||||
//비상정지 반전
|
||||
diValue[IDXI_EMG] = !diValue[IDXI_EMG];
|
||||
|
||||
//오버로드센서 반전
|
||||
diValue[IDXI_OVERLOADL] = !diValue[IDXI_OVERLOADL];
|
||||
diValue[IDXI_OVERLOADR] = !diValue[IDXI_OVERLOADR];
|
||||
diValue[IDXI_EMPTY7] = !diValue[IDXI_EMPTY7];
|
||||
diValue[IDXI_EMPTY8] = !diValue[IDXI_EMPTY8];
|
||||
|
||||
//오버로드센서를 합친다 5+6=>5, 7+8=>6
|
||||
diValue[IDXI_OVERLOADL] = diValue[IDXI_OVERLOADL] || diValue[IDXI_OVERLOADR];
|
||||
diValue[IDXI_OVERLOADR] = diValue[IDXI_EMPTY7] || diValue[IDXI_EMPTY8];
|
||||
diValue[IDXI_EMPTY7]= false;
|
||||
diValue[IDXI_EMPTY8]= false;
|
||||
|
||||
//리밋센서도 반전
|
||||
diValue[IDXI_LIMIT_LU] = !diValue[IDXI_LIMIT_LU];
|
||||
diValue[IDXI_LIMIT_LD] = !diValue[IDXI_LIMIT_LD];
|
||||
diValue[IDXI_LIMIT_RU] = !diValue[IDXI_LIMIT_RU];
|
||||
diValue[IDXI_LIMIT_RD] = !diValue[IDXI_LIMIT_RD];
|
||||
|
||||
//리버스 체크 200325
|
||||
//입력값은 Reverse 하지 않는다
|
||||
/*
|
||||
var._eep_pindir_iL = 0;
|
||||
var._eep_pindir_iH = 0;
|
||||
|
||||
for (int i = 0; i < 16; i++)
|
||||
{
|
||||
if (i < 8)
|
||||
{
|
||||
if (bitRead(var._eep_pindir_iL, i) == true)
|
||||
diValue[i] = !diValue[i];
|
||||
}
|
||||
else {
|
||||
if (bitRead(var._eep_pindir_iH, i - 8) == true)
|
||||
diValue[i] = !diValue[i];
|
||||
}
|
||||
}*/
|
||||
|
||||
|
||||
for (int i = 0; i < idx; i++)
|
||||
{
|
||||
//이 값의 변화를 체크한다.
|
||||
bool oldValue = bitRead(var.IOData, i);
|
||||
bool isNewValue = false;
|
||||
if (oldValue != diValue[i]) isNewValue = true;
|
||||
bitWrite(var.IOData, i, diValue[i]);//0번부터 기록한다
|
||||
|
||||
//값이 변화했따
|
||||
if (isNewValue) IOValueChanged(false, i, diValue[i]);
|
||||
}
|
||||
|
||||
//read output
|
||||
bool doValue[8]; idx = 0;
|
||||
doValue[idx++] = digitalRead(PINO_GUIDEMOTOR_LDIR);
|
||||
doValue[idx++] = digitalRead(PINO_GUIDEMOTOR_LRUN);
|
||||
doValue[idx++] = digitalRead(PINO_GUIDEMOTOR_RDIR);
|
||||
doValue[idx++] = digitalRead(PINO_GUIDEMOTOR_RRUN);
|
||||
doValue[idx++] = digitalRead(PINO_EMPTY_26);
|
||||
doValue[idx++] = digitalRead(PINO_EMPTY_27);
|
||||
doValue[idx++] = digitalRead(PINO_EMPTY_28);
|
||||
doValue[idx++] = digitalRead(PINO_EMPTY_29);
|
||||
|
||||
for (int i = 0; i < idx; i++)
|
||||
{
|
||||
bool oldValue = bitRead(var.IOData, i + 16);
|
||||
bool isNewValue = false;
|
||||
if (oldValue != doValue[i]) isNewValue = true;
|
||||
bitWrite(var.IOData, i + 16, doValue[i]);//0번부터 기록한다
|
||||
|
||||
//값이 변화했따
|
||||
if (isNewValue) IOValueChanged(true, i, !oldValue);
|
||||
}
|
||||
|
||||
//Read Analog (마그넷 센서 값만 확인한다)
|
||||
idx = 0;
|
||||
|
||||
//원본값은 그대로 저장한다
|
||||
var.ANData[idx++] = analogRead(PINAI_0);
|
||||
var.ANData[idx++] = analogRead(PINAI_1);
|
||||
var.ANData[idx++] = analogRead(PINAI_2);
|
||||
var.ANData[idx++] = analogRead(PINAI_3);
|
||||
|
||||
idx = 0;
|
||||
var.AOData[idx++] = 0;
|
||||
var.AOData[idx++] = 0;
|
||||
var.AOData[idx++] = 0;
|
||||
var.AOData[idx++] = 0;
|
||||
|
||||
//파워체크
|
||||
if (IsPowerLoss() == true) var.setFlag(FLAG_POWERLOSS, true, "IOUpdate");
|
||||
else var.setFlag(FLAG_POWERLOSS, false, "IOUpdate");
|
||||
}
|
||||
|
||||
//메인전원이 OFF되어있는지 확인합니다.(리밋센서의OFF여부로 체크함)
|
||||
bool IoClass::IsPowerLoss()
|
||||
{
|
||||
//얘들은 B접점이라서. 항상 ON 이 되어있는 애들이다.
|
||||
//전원이 OFF되면 모든 센서가 LOW 상태가 된다
|
||||
//하지만 신호를 반전(!) 시켜두었으므로 모두 켜진다면 OFF 된 경우이다)
|
||||
bool b1 = bitRead(var.IOData, IDXI_LIMIT_LD);
|
||||
bool b2 = bitRead(var.IOData, IDXI_LIMIT_LU);
|
||||
bool b3 = bitRead(var.IOData, IDXI_LIMIT_RU);
|
||||
bool b4 = bitRead(var.IOData, IDXI_LIMIT_RD);
|
||||
if (b1 == true && b2 == true && b3 == true && b4 == true) return true;
|
||||
return false;
|
||||
}
|
||||
|
||||
//IO상태값이 변화되었을때 동작한다
|
||||
void IoClass::IOValueChanged(bool isout, uint8_t index, bool newValue)
|
||||
{
|
||||
if (isout == false) //입력포트
|
||||
{
|
||||
|
||||
if (index == IDXI_BTN_1)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
hmi.SendMessage("button 1 pressed", false);
|
||||
}
|
||||
}
|
||||
if (index == IDXI_BTN_2)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
hmi.SendMessage("button 2 pressed", false);
|
||||
}
|
||||
}
|
||||
if (index == IDXI_BTN_3)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
hmi.SendMessage("button 3 pressed", false);
|
||||
}
|
||||
}
|
||||
if (index == IDXI_BTN_4)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
hmi.SendMessage("button 4 pressed", false);
|
||||
}
|
||||
}
|
||||
|
||||
//양쪽면의 z축 UP/DN 버튼 할당
|
||||
if (index == IDXI_BTN_ZUP)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
if (mot.GetZDirL() == ZDIR_CW && mot.IsMoveZ() == true)
|
||||
{
|
||||
hmi.SendMessage("z-stop by h/w button", false);
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
if (mot.GetZDirL() == ZDIR_CCW && mot.IsMoveZ() == true)
|
||||
{
|
||||
hmi.SendMessage("z-stop by h/w button", false);
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
else {
|
||||
mot.SetZRun(ZRUN_UP);
|
||||
hmi.SendMessage("Z-Up by H/W Button", false);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_BTN_ZDN)
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
if (mot.GetZDirL() == ZDIR_CCW && mot.IsMoveZ() == true)
|
||||
{
|
||||
hmi.SendMessage("z-stop by h/w button", false);
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
if (mot.GetZDirL() == ZDIR_CW && mot.IsMoveZ() == true)
|
||||
{
|
||||
hmi.SendMessage("z-stop by h/w button", false);
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
else {
|
||||
mot.SetZRun(ZRUN_DN);
|
||||
hmi.SendMessage("Z-Dn by H/W Button", false);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_EMG) //비상정지 혹은 범퍼센서가 감지된경우
|
||||
{
|
||||
if (newValue == true)
|
||||
{
|
||||
hmi.SendMessage("EMG Stop Detected", false);
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
}
|
||||
|
||||
//일반적으로 Rising 상태일때에만 동작시킨다.
|
||||
if (newValue == true)
|
||||
{
|
||||
//하단센서2개가 들어왔다면 FLAG를 설정한다
|
||||
if (index == IDXI_LIMIT_LD || index == IDXI_LIMIT_RD)
|
||||
{
|
||||
if (index == IDXI_LIMIT_LD )
|
||||
{
|
||||
if (var.getFlag(FLAG_LIMITLOWL) == false)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWL, true, "IO:Limit Sensor(LD) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMITL:1"), false);
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_LIMIT_RD )
|
||||
{
|
||||
if (var.getFlag(FLAG_LIMITLOWR) == false)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWR, true, "IO:Limit Sensor(RD) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMITR:1"), false);
|
||||
}
|
||||
}
|
||||
else {
|
||||
bool b1 = bitRead(var.IOData, IDXI_LIMIT_LD);
|
||||
bool b2 = bitRead(var.IOData, IDXI_LIMIT_RD);
|
||||
if (b1 == false && var.getFlag(FLAG_LIMITLOWL) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWL, false, "IO:Limit Sensor(LD) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMITL:0"), false);
|
||||
}
|
||||
if (b2 == false && var.getFlag(FLAG_LIMITLOWR) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWR, false, "IO:Limit Sensor(RD) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMITR:0"), false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (index == IDXI_LIMIT_LU || index == IDXI_LIMIT_RU)
|
||||
{
|
||||
|
||||
|
||||
if (index == IDXI_LIMIT_LU || var.getFlag(FLAG_LIMITHIGHL) == false)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHL, true, "IO:Limit Sensor(LU) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMITL:1"), false);
|
||||
}
|
||||
else if (index == IDXI_LIMIT_RU || var.getFlag(FLAG_LIMITHIGHR) == false)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHR, true, "IO:Limit Sensor(RU) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMITR:1"), false);
|
||||
}
|
||||
else {
|
||||
bool b1 = bitRead(var.IOData, IDXI_LIMIT_LU);
|
||||
bool b2 = bitRead(var.IOData, IDXI_LIMIT_RU);
|
||||
if (b1 == false && var.getFlag(FLAG_LIMITHIGHL) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHL, false, "IO:Limit Sensor(LU) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMITL:0"), false);
|
||||
}
|
||||
if (b2 == false && var.getFlag(FLAG_LIMITHIGHR) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHR, false, "IO:Limit Sensor(RU) Changed");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMITR:0"), false);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//오버로드 플래그 활성화
|
||||
if (index == IDXI_OVERLOADL)
|
||||
{
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
hmi.SendMessage(F("All Mot Stop by OverloadL"), false);
|
||||
}
|
||||
else if (index == IDXI_OVERLOADR)
|
||||
{
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
hmi.SendMessage(F("All Mot Stop by OverloadR"), false);
|
||||
}
|
||||
|
||||
}
|
||||
else //해당값이 OFF 되었다
|
||||
{
|
||||
|
||||
//대상이 리밋센서라면 플래그를 설정 해준다
|
||||
if (index == IDXI_LIMIT_LD)
|
||||
{
|
||||
|
||||
hmi.SendMessage("Limit Sensor(LD) Change " + String(index) + "=" + String(newValue), false);
|
||||
if (var.getFlag(FLAG_LIMITLOWL) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWL, false, "IO:Limit Sensor Changed(LD)");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMIT:0"), false);
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_LIMIT_RD)
|
||||
{
|
||||
|
||||
hmi.SendMessage("Limit Sensor(RD) Change " + String(index) + "=" + String(newValue), false);
|
||||
if (var.getFlag(FLAG_LIMITLOWR) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITLOWR, false, "IO:Limit Sensor Changed(RD)");
|
||||
hmi.SendMessage(F("SET:FLAG:LOW_LIMIT:0"), false);
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_LIMIT_LU )
|
||||
{
|
||||
hmi.SendMessage("Limit Sensor(LU) Change " + String(index) + "=" + String(newValue), false);
|
||||
if (var.getFlag(FLAG_LIMITHIGHL) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHL, false, "IO:Limit Sensor Changed(LU)");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMIT:0"), false);
|
||||
}
|
||||
}
|
||||
else if (index == IDXI_LIMIT_RU)
|
||||
{
|
||||
hmi.SendMessage("Limit Sensor(RU) Change " + String(index) + "=" + String(newValue), false);
|
||||
if (var.getFlag(FLAG_LIMITHIGHR) == true)
|
||||
{
|
||||
var.setFlag(FLAG_LIMITHIGHR, false, "IO:Limit Sensor Changed(RU)");
|
||||
hmi.SendMessage(F("SET:FLAG:HIGH_LIMIT:0"), false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else //출력포트
|
||||
{
|
||||
//일반적으로 Rising 상태일때에만 동작시킨다.
|
||||
if (newValue == true)
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
IoClass io;
|
||||
136
Arduino_PLC/IO.h
Normal file
136
Arduino_PLC/IO.h
Normal file
@@ -0,0 +1,136 @@
|
||||
#ifndef _IO_H_
|
||||
#define _IO_H_
|
||||
#include "Arduino.h"
|
||||
|
||||
class IoClass
|
||||
{
|
||||
public:
|
||||
|
||||
//input pin
|
||||
#define PINI_EMG 30
|
||||
#define PINI_BTN_1 31
|
||||
#define PINI_BTN_2 32
|
||||
#define PINI_BTN_3 33
|
||||
#define PINI_BTN_4 34
|
||||
|
||||
#define PINI_OVERLOADL1 35
|
||||
#define PINI_OVERLOADL2 36
|
||||
|
||||
#define PINI_OVERLOADR1 37
|
||||
#define PINI_OVERLOADR2 38
|
||||
|
||||
#define PINI_EMPTY_38 39
|
||||
|
||||
#define PINI_BTN_ZUP 40
|
||||
#define PINI_BTN_ZDN 41
|
||||
#define PINI_LIMIT_LU 42
|
||||
#define PINI_LIMIT_LD 43
|
||||
#define PINI_LIMIT_RU 44
|
||||
#define PINI_LIMIT_RD 45
|
||||
#define PINI_STOP 46
|
||||
|
||||
//send data index
|
||||
#define IDXI_EMG 0
|
||||
#define IDXI_BTN_1 1
|
||||
#define IDXI_BTN_2 2
|
||||
#define IDXI_BTN_3 3
|
||||
#define IDXI_BTN_4 4
|
||||
#define IDXI_OVERLOADL 5
|
||||
#define IDXI_OVERLOADR 6
|
||||
#define IDXI_EMPTY7 7
|
||||
#define IDXI_EMPTY8 8
|
||||
#define IDXI_BTN_ZUP 9
|
||||
#define IDXI_BTN_ZDN 10
|
||||
#define IDXI_LIMIT_LU 11
|
||||
#define IDXI_LIMIT_LD 12
|
||||
#define IDXI_LIMIT_RU 13
|
||||
#define IDXI_LIMIT_RD 14
|
||||
#define IDXI_STOP 15
|
||||
|
||||
//output
|
||||
#define PINO_GUIDEMOTOR_LDIR 22 //Guide Motor Direction
|
||||
#define PINO_GUIDEMOTOR_LRUN 23 //Guide Motor Start
|
||||
#define PINO_GUIDEMOTOR_RDIR 24 //
|
||||
#define PINO_GUIDEMOTOR_RRUN 25 //Guide Motor Run(STA<54><41> <20><><EFBFBD><EFBFBD>ȭ<EFBFBD><C8AD> [IO.cpp:Update()] )
|
||||
#define PINO_EMPTY_26 26
|
||||
#define PINO_EMPTY_27 27
|
||||
#define PINO_EMPTY_28 28
|
||||
#define PINO_EMPTY_29 29
|
||||
|
||||
|
||||
#define IDXO_GUIDEMOTOR_LDIR 0 //Guide Motor Direction
|
||||
#define IDXO_GUIDEMOTOR_LRUN 1 //Guide Motor Start
|
||||
#define IDXO_GUIDEMOTOR_RDIR 2 //
|
||||
#define IDXO_GUIDEMOTOR_RRUN 3 //Guide Motor Run(STA<54><41> <20><><EFBFBD><EFBFBD>ȭ<EFBFBD><C8AD> [IO.cpp:Update()] )
|
||||
#define IDXO_EMPTY_04 4
|
||||
#define IDXO_EMPTY_05 5
|
||||
#define IDXO_EMPTY_06 6
|
||||
#define IDXO_EMPTY_07 7
|
||||
#define IDXO_EMPTY_08 8
|
||||
#define IDXO_CHARGE_ON 9
|
||||
#define IDXO_MOT_POWER_L 10
|
||||
#define IDXO_MOT_POWER_R 11
|
||||
#define IDXO_EMPTY_42 12
|
||||
#define IDXO_EMPTY_43 13
|
||||
#define IDXO_EMPTY_44 14
|
||||
#define IDXO_EMPTY_45 15
|
||||
|
||||
//<2F>Ƴ<EFBFBD><C6B3>α<EFBFBD><CEB1>Է<EFBFBD>(<28>ɹ<EFBFBD>ȣ)
|
||||
#define PINAI_0 A0 //<2F><><EFBFBD>׳ݼ<D7B3><DDBC><EFBFBD>(FRONT) <20><>ġ <20><>
|
||||
#define PINAI_1 A1 //<2F><><EFBFBD>׳ݼ<D7B3><DDBC><EFBFBD>(REAR) <20><>ġ <20><>
|
||||
#define PINAI_2 A2 //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
#define PINAI_3 A3 //<2F><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD> <20>б<EFBFBD>
|
||||
|
||||
//<2F>Ƴ<EFBFBD><C6B3>α<EFBFBD> <20>Է<EFBFBD>(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD>)
|
||||
#define IDXAI_0 0
|
||||
#define IDXAI_1 1
|
||||
#define IDXAI_2 2
|
||||
#define IDXAI_3 3
|
||||
|
||||
//<2F>Ƴ<EFBFBD><C6B3>α<EFBFBD><CEB1><EFBFBD><EFBFBD>(PWM)
|
||||
#define PINAO_4 A4 //Z<><5A> <20><><EFBFBD><EFBFBD> <20>ӵ<EFBFBD>
|
||||
#define PINAO_5 A5 //<2F><><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD> <20>ӵ<EFBFBD>
|
||||
#define PINAO_6 A6 //<2F><><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD> <20>ӵ<EFBFBD>
|
||||
#define PINAO_7 A7 //<2F><><EFBFBD><EFBFBD><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD> <20>ӵ<EFBFBD>
|
||||
|
||||
//<2F>Ƴ<EFBFBD><C6B3>α<EFBFBD><CEB1><EFBFBD><EFBFBD>(<28><><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20>ε<EFBFBD><CEB5><EFBFBD>)
|
||||
#define IDXAO_0 0 //Z<><5A> <20><><EFBFBD><EFBFBD> <20>ӵ<EFBFBD>
|
||||
#define IDXAO_1 1 //(<28><>+<2B><>) <20><><EFBFBD><EFBFBD>
|
||||
#define IDXAO_2 2 //<2F><><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD> <20>ӵ<EFBFBD>
|
||||
#define IDXAO_3 3 //<2F><><EFBFBD><EFBFBD><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD> <20>ӵ<EFBFBD>
|
||||
|
||||
#define MAF_SIZE 30
|
||||
|
||||
void Setup();
|
||||
void Update();
|
||||
bool IsPowerLoss();
|
||||
private:
|
||||
|
||||
int bufferF[MAF_SIZE];
|
||||
int indexF = 0;
|
||||
int countF = 0;
|
||||
int iF;
|
||||
int sumF = 0;
|
||||
int tempF;
|
||||
float avgF;
|
||||
|
||||
int bufferB[MAF_SIZE];
|
||||
int indexB = 0;
|
||||
int countB = 0;
|
||||
int iB;
|
||||
int sumB = 0;
|
||||
int tempB;
|
||||
float avgB;
|
||||
|
||||
long tm_gateoutOn = 0;
|
||||
long tm_gateoutOf = 0;
|
||||
long tm_markOn = 0;
|
||||
long tm_markOff = 0;
|
||||
|
||||
unsigned long runtime = 0;
|
||||
void IOValueChanged(bool isout, uint8_t index, bool newValue);
|
||||
|
||||
};
|
||||
|
||||
extern IoClass io;
|
||||
#endif
|
||||
1
Arduino_PLC/ReadMe.txt
Normal file
1
Arduino_PLC/ReadMe.txt
Normal file
@@ -0,0 +1 @@
|
||||
221116 B라인용 소스 정리 작업 진행
|
||||
0
Arduino_PLC/StructInfo.txt
Normal file
0
Arduino_PLC/StructInfo.txt
Normal file
21
Arduino_PLC/UtilClass.cpp
Normal file
21
Arduino_PLC/UtilClass.cpp
Normal file
@@ -0,0 +1,21 @@
|
||||
#include "UtilClass.h"
|
||||
#include "VarClass.h"
|
||||
#include "arduino.h"
|
||||
|
||||
uint32_t UtilClass::b2i(bool Value)
|
||||
{
|
||||
if (Value == true) return 1;
|
||||
else return 0;
|
||||
}
|
||||
|
||||
uint8_t UtilClass::spdConvPercToValue(uint8_t perc)
|
||||
{
|
||||
uint8_t retval = map(perc, 0, 100, 0, 255); // perc / 100 * 255;
|
||||
return retval; //,0,255,0,100));
|
||||
}
|
||||
|
||||
void UtilClass::copy(byte* src, byte* dst, byte len) {
|
||||
memcpy(dst, src, sizeof(src[0])*len);
|
||||
}
|
||||
|
||||
UtilClass util;
|
||||
17
Arduino_PLC/UtilClass.h
Normal file
17
Arduino_PLC/UtilClass.h
Normal file
@@ -0,0 +1,17 @@
|
||||
#ifndef _UTILCLASS_H_
|
||||
#define _UTILCLASS_H_
|
||||
#include "arduino.h"
|
||||
|
||||
class UtilClass
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
void copy(byte* src, byte* dst, byte len);
|
||||
uint32_t b2i(bool Value);
|
||||
uint8_t spdConvPercToValue(uint8_t perc);
|
||||
|
||||
//void debug(char *str, ...);
|
||||
};
|
||||
extern UtilClass util;
|
||||
#endif
|
||||
271
Arduino_PLC/VarClass.cpp
Normal file
271
Arduino_PLC/VarClass.cpp
Normal file
@@ -0,0 +1,271 @@
|
||||
#include "VarClass.h"
|
||||
#include "motor.h"
|
||||
#include "IO.h"
|
||||
#include "HmiClass.h"
|
||||
|
||||
|
||||
void VarClass::Setup()
|
||||
{
|
||||
hmi.SendMessage("##:VAR:SETUP", false);
|
||||
|
||||
for(int i = 0 ; i < 4;i++)
|
||||
{
|
||||
ANData[i] = 0;
|
||||
AOData[i] = 0;
|
||||
}
|
||||
}
|
||||
void VarClass::Update()
|
||||
{
|
||||
/*
|
||||
if (var.getFlag(FLAG_CHARGEONM) == true)
|
||||
{
|
||||
//<2F><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>̶<EFBFBD><CCB6> <20>ڵ<EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>¸<EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>Ѵ<EFBFBD>
|
||||
if (var.getFlag(FLAG_AUTORUN) == true)
|
||||
var.setFlag(FLAG_AUTORUN, false, "Manual Charge Mode");
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
/* <20>ܺθ<DCBA><CEB8><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>մϴ<D5B4>. HMI<4D><49> <20><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD>̳<EFBFBD> RS232<33><32> REMOTE <20><>ɿ<EFBFBD> <20><><EFBFBD><EFBFBD> */
|
||||
void VarClass::runCommand(eCommand cmd, uint8_t p1, uint8_t p2)
|
||||
{
|
||||
/*String msg = ("RunCommand ");
|
||||
msg += String(cmd);
|
||||
msg += (":");
|
||||
msg += String(p1);
|
||||
msg += (":");
|
||||
msg += String(p2);
|
||||
hmi.SendMessage(msg, false);*/
|
||||
|
||||
//display data
|
||||
var.pingtime = millis();
|
||||
bool newValue = false;
|
||||
|
||||
if (cmd == LOAD)
|
||||
{
|
||||
var.eeprom_load();
|
||||
}
|
||||
else if (cmd == SAVE)
|
||||
{
|
||||
var.eeprom_save();
|
||||
}
|
||||
else if (cmd == RESET)
|
||||
{
|
||||
var.runReset = true;
|
||||
}
|
||||
else if (cmd == SET_PINMODE)
|
||||
{
|
||||
pinMode(p1, p2); //<2F>ش<EFBFBD><D8B4><EFBFBD><EFBFBD><EFBFBD> IO<49><4F>带 <20><><EFBFBD><EFBFBD><EFBFBD>Ѵ<EFBFBD>
|
||||
}
|
||||
else if (cmd == SET_DOUTPUT)
|
||||
{
|
||||
String msg = ("Remote:Output:");
|
||||
msg += String(p1);
|
||||
msg += ',';
|
||||
msg += String(p2);
|
||||
hmi.SendMessage(msg, false);
|
||||
digitalWrite(p1, p2);
|
||||
}
|
||||
else if (cmd == SET_AOUTPUT)
|
||||
{
|
||||
if (p1 == 11) var.AOData[0] = p2;
|
||||
else if (p1 == 12) var.AOData[1] = p2;
|
||||
|
||||
analogWrite(p1, p2);
|
||||
|
||||
String msg = ("Set PWM Out:");
|
||||
msg += String(p1);
|
||||
msg += ',';
|
||||
msg += String(p2);
|
||||
hmi.SendMessage(msg, false);
|
||||
}
|
||||
else if (cmd == SET_FLAG)
|
||||
{
|
||||
String msg = ("@FLAG|");
|
||||
msg += String(p1);
|
||||
msg += ',';
|
||||
msg += String(p2);
|
||||
hmi.SendMessage(msg, false);
|
||||
|
||||
if (p2 == 1) var.setFlag(p1, true, "Remote");
|
||||
else var.setFlag(p1, false, "Remote");
|
||||
|
||||
if (p2 == 1 && p1 == FLAG_SETUP)
|
||||
{
|
||||
hmi.SendMessage("Entering Setup Mode", false);
|
||||
}
|
||||
}
|
||||
else if (cmd == SET_EEPROM)
|
||||
{
|
||||
if (p1 == EEP_IOINTERVAL) {
|
||||
var._eep_iosendinterval = p2;
|
||||
hmi.SendMessage("(EEP) I/O Interval = " + String(p2), false);
|
||||
}
|
||||
else if (p1 == EEP_RESETCOUNT) {
|
||||
hmi.SendMessage("(EEP) EEP_RESETCOUNT = " + String(p2), false);
|
||||
}
|
||||
else hmi.SendMessage("Set_ErrpRom p1 error", false);
|
||||
//var.eeprom_save();
|
||||
}
|
||||
else if (cmd == GET_SETTING)
|
||||
{
|
||||
//<2F><><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>Ѵ<EFBFBD>
|
||||
//<2F>̰DZ<CCB0><C7B1><EFBFBD><EFBFBD>ؾ<EFBFBD><D8BE><EFBFBD>
|
||||
}
|
||||
|
||||
else if (cmd == GUIDE_MOT)
|
||||
{
|
||||
if (p1 == 'L') //left
|
||||
{
|
||||
if (p2 == 'P')
|
||||
{
|
||||
mot.SetZDir(ZDIR_CW);
|
||||
mot.SetZRunL(true);
|
||||
}
|
||||
else if (p2 == 'N')
|
||||
{
|
||||
mot.SetZDir(ZDIR_CCW);
|
||||
mot.SetZRunL(true);
|
||||
}
|
||||
else if (p2 == 'S')
|
||||
{
|
||||
mot.SetZRunL(false);
|
||||
}
|
||||
}
|
||||
else if (p1 == 'R') //right
|
||||
{
|
||||
if (p2 == 'P')
|
||||
{
|
||||
mot.SetZDir(ZDIR_CW);
|
||||
mot.SetZRunR(true);
|
||||
}
|
||||
else if (p2 == 'N')
|
||||
{
|
||||
mot.SetZDir(ZDIR_CCW);
|
||||
mot.SetZRunR(true);
|
||||
}
|
||||
else if (p2 == 'S')
|
||||
{
|
||||
mot.SetZRunR(false);
|
||||
}
|
||||
}
|
||||
else if (p1 == 'A') //all
|
||||
{
|
||||
if (p2 == 'P')
|
||||
{
|
||||
mot.SetZRun(ZRUN_UP);
|
||||
}
|
||||
else if (p2 == 'N')
|
||||
{
|
||||
mot.SetZRun(ZRUN_DN);
|
||||
}
|
||||
else if (p2 == 'S')
|
||||
{
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (cmd == PINGCHK)
|
||||
{
|
||||
//<2F>ƹ<EFBFBD><C6B9>͵<EFBFBD> ó<><C3B3><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20>ʴ´<CAB4>.
|
||||
}
|
||||
else {
|
||||
hmi.SendMessage(F("Unknown Command"), true);
|
||||
}
|
||||
}
|
||||
|
||||
void VarClass::eeprom_save()
|
||||
{
|
||||
//param
|
||||
EEPROM.write(EEP_IOINTERVAL, var._eep_iosendinterval);
|
||||
EEPROM.write(EEP_RESETCOUNT, var._eep_resetcount);
|
||||
EEPROM.write(EEP_DIREVH, var._eep_pindir_iH);
|
||||
EEPROM.write(EEP_DIREVL, var._eep_pindir_iL);
|
||||
|
||||
//<2F>ɼǰ<C9BC> <20><><EFBFBD><EFBFBD>
|
||||
bool opt1 = var.getFlag(FLAG_ENABLE_AD4INVERT);
|
||||
bool opt2 = var.getFlag(FLAG_ENABLE_LOG_SPEED);
|
||||
//bool opt3 = var.getFlag(FLAG_ENABLE_BALANCE);
|
||||
//bool opt4 = var.getFlag(FLAG_ENABLE_LIDARSTOP);
|
||||
//bool opt5 = var.getFlag(FLAG_ENABLE_GATEOUT);
|
||||
|
||||
bitWrite(var._eep_option, FLAG_ENABLE_AD4INVERT - 24, opt1);
|
||||
bitWrite(var._eep_option, FLAG_ENABLE_LOG_SPEED - 24, opt2);
|
||||
//bitWrite(var._eep_option, FLAG_ENABLE_BALANCE - 24, opt3);
|
||||
//bitWrite(var._eep_option, FLAG_ENABLE_LIDARSTOP - 24, opt4);
|
||||
//bitWrite(var._eep_option, FLAG_ENABLE_GATEOUT - 24, opt5);
|
||||
|
||||
//hmi.SendMessage("Option Store Value=" + String(var._eep_option), false);
|
||||
EEPROM.write(EEP_OPTION, var._eep_option); //<2F><><EFBFBD><EFBFBD> 200402
|
||||
hmi.SendMessage("@SET|SAVE:" + String(var._eep_option), false);
|
||||
}
|
||||
|
||||
void VarClass::eeprom_load()
|
||||
{
|
||||
//hmi.SendMessage("##:EEPROM:LOAD:BEGIN", false);
|
||||
var._eep_iosendinterval = EEPROM.read(EEP_IOINTERVAL);
|
||||
var._eep_resetcount = EEPROM.read(EEP_RESETCOUNT);
|
||||
var._eep_pindir_iH = EEPROM.read(EEP_DIREVH);
|
||||
var._eep_pindir_iL = EEPROM.read(EEP_DIREVL);
|
||||
var._eep_option = EEPROM.read(EEP_OPTION); //<2F>ɼǰ<C9BC><C7B0><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD>س<EFBFBD><D8B3><EFBFBD> <20><><EFBFBD><EFBFBD>Ѵ<EFBFBD>
|
||||
|
||||
//<2F>ɼǰ<C9BC> <20><><EFBFBD><EFBFBD>
|
||||
bool opt1 = bitRead(var._eep_option, FLAG_ENABLE_AD4INVERT - 24);
|
||||
bool opt2 = bitRead(var._eep_option, FLAG_ENABLE_LOG_SPEED - 24);
|
||||
|
||||
|
||||
if (var._eep_iosendinterval == 0 || var._eep_iosendinterval == 0xFF)
|
||||
var._eep_iosendinterval = 50;
|
||||
|
||||
|
||||
|
||||
hmi.SendMessage("@SET|LOAD:" + String(var._eep_option), false);
|
||||
}
|
||||
|
||||
void VarClass::eeprom_incResetCount()
|
||||
{
|
||||
EEPROM.write(EEP_RESETCOUNT, _eep_resetcount);
|
||||
hmi.SendMessage(F("Increase Reset Count"), false);
|
||||
}
|
||||
|
||||
/*
|
||||
system flag
|
||||
*/
|
||||
void VarClass::setFlag(uint8_t pos, bool value, String Readson)
|
||||
{
|
||||
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ȯ<EFBFBD><C8AE>
|
||||
bool oldValue = bitRead(var.flag, pos);
|
||||
|
||||
//#####################################
|
||||
// 값이 변경된 경우에 처리
|
||||
//#####################################
|
||||
if (oldValue != value)
|
||||
{
|
||||
bitWrite(var.flag, pos, value);
|
||||
|
||||
if (pos == FLAG_AUTORUN)
|
||||
{
|
||||
if (value == true)
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
else if (pos == FLAG_STOPZ)
|
||||
{
|
||||
hmi.SendMessage("Z-Stop Condition => " + String(value) + ": " + Readson, false);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
bool VarClass::getFlag(uint8_t pos)
|
||||
{
|
||||
return bitRead(var.flag, pos);
|
||||
}
|
||||
uint32_t VarClass::getFlagValue()
|
||||
{
|
||||
return var.flag;
|
||||
}
|
||||
|
||||
VarClass var;
|
||||
119
Arduino_PLC/VarClass.h
Normal file
119
Arduino_PLC/VarClass.h
Normal file
@@ -0,0 +1,119 @@
|
||||
#ifndef _VAR_H_
|
||||
#define _VAR_H_
|
||||
|
||||
#define DEBUG
|
||||
#define sprint(...) Serial1.print(__VA_ARGS__)
|
||||
#define sprintln(...) Serial1.println(__VA_ARGS__)
|
||||
#ifdef DEBUG
|
||||
#define dprint(...) Serial1.print(__VA_ARGS__)
|
||||
#define dprintln(...) Serial1.println(__VA_ARGS__)
|
||||
#else
|
||||
#define dprint(...)
|
||||
#define dprint(...)
|
||||
#endif
|
||||
|
||||
|
||||
#include "arduino.h"
|
||||
#include <EEPROM.h>
|
||||
#include "UtilClass.h"
|
||||
|
||||
//모든 사용가능한 커맨드를 넣는다(이 파일은 서브PLC파일)
|
||||
enum eCommand
|
||||
{
|
||||
LOAD = 0, //EEPROM 불러오기
|
||||
SAVE, //EEPROM 저장
|
||||
RESET, //초기화
|
||||
PINGCHK,
|
||||
SET_PINMODE, //PINMODE 설정
|
||||
SET_DOUTPUT, //디지털출력설정(포트번호,값[1,0])
|
||||
SET_AOUTPUT, //아날로그출력설정(포트GET_SETTING = 50, //셋팅값 요청
|
||||
SET_FLAG,
|
||||
SET_EEPROM,
|
||||
SET_MANUALSPEED,
|
||||
GET_SETTING = 50,
|
||||
GUIDE_MOT= 90, //가이드커버(양쪽) 0=멈춤,1=UP,2=DN 아스키코드표 90=Z
|
||||
SET_EEP_DIREV,
|
||||
};
|
||||
|
||||
//asci 0=48,1=49,2=50
|
||||
|
||||
enum eEEPAddress
|
||||
{
|
||||
EEP_IOINTERVAL = 0,
|
||||
EEP_RESETCOUNT,
|
||||
EEP_DIREVH,
|
||||
EEP_DIREVL,
|
||||
EEP_OPTION,
|
||||
EEP_UPTIME,
|
||||
};
|
||||
|
||||
//플래그 총 32개 모두 다씀
|
||||
enum eFlag
|
||||
{
|
||||
FLAG_STOPZ= 0,
|
||||
FLAG_SETUP,
|
||||
FLAG_WAIT,
|
||||
FLAG_AUTORUN,
|
||||
FLAG_MANUALRUN,
|
||||
FLAG_LIMITHIGHL,
|
||||
FLAG_LIMITHIGHR,
|
||||
FLAG_LIMITLOWL,
|
||||
FLAG_LIMITLOWR,
|
||||
FLAG_POWERLOSS,
|
||||
FLAG_DIR,
|
||||
FLAG_LEFT_RUN,
|
||||
FLAG_RIGHT_RUN,
|
||||
FLAG_RUN_CMD,
|
||||
FLAG_GO_CHAGER = 26,
|
||||
FLAG_ENABLE_AD4INVERT=27,
|
||||
FLAG_ENABLE_LOG_SPEED = 28,
|
||||
};
|
||||
|
||||
class VarClass
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
unsigned long serialprinttime = 0;
|
||||
uint16_t runtime = 0;
|
||||
long pingtime = 0;
|
||||
|
||||
//SUB
|
||||
|
||||
uint32_t IOData = 0; //IO데이터가 있으며 DI : Low 16bit, DO : High 16bit
|
||||
uint8_t ANData[4]; //A0 ~ A3
|
||||
uint8_t AOData[4]; //A4 ~ A6
|
||||
|
||||
void Setup();
|
||||
void Update();
|
||||
void runCommand(eCommand cmd, uint8_t p1, uint8_t p2);
|
||||
|
||||
uint8_t _eep_resetcount = 0; //장치초기화 횟수
|
||||
uint8_t _eep_iosendinterval = 0;
|
||||
|
||||
uint8_t _eep_option = 0; //옵션값(이 값은 FLAG와 연결됨)
|
||||
|
||||
uint8_t _eep_pindir_iH = 0; //Input High
|
||||
uint8_t _eep_pindir_iL = 0; //Input Low
|
||||
|
||||
uint8_t manual_speed = 0; //속도고정값
|
||||
|
||||
void eeprom_save(); //EEPROM 쓰기
|
||||
void eeprom_load(); //EEPROM 읽기
|
||||
void eeprom_incResetCount(); //초기화횟수증가 및 저장
|
||||
|
||||
void setFlag(uint8_t pos, bool value, String Readson); //플래그쓰기
|
||||
bool getFlag(uint8_t pos); //플래그읽기
|
||||
uint32_t getFlagValue(); //플래그값확인
|
||||
|
||||
bool runReset = false; //이값을 설정하면 Project.Ino 에서 초기화를 수행함
|
||||
|
||||
private:
|
||||
|
||||
uint32_t flag = 0; //시스템플래그
|
||||
uint32_t flag_ = 0;
|
||||
//void FlagValueChanged(uint8_t index, bool newValue);
|
||||
};
|
||||
|
||||
extern VarClass var;
|
||||
#endif
|
||||
256
Arduino_PLC/motor.cpp
Normal file
256
Arduino_PLC/motor.cpp
Normal file
@@ -0,0 +1,256 @@
|
||||
#include "motor.h"
|
||||
#include "IO.h"
|
||||
#include "VarClass.h"
|
||||
#include "UtilClass.h"
|
||||
#include "HmiClass.h"
|
||||
|
||||
void motor::Setup()
|
||||
{
|
||||
hmi.SendMessage("##:MOT:SETUP", false);
|
||||
|
||||
//Z축 멈춤
|
||||
SetZRun(ZRUN_STOP);
|
||||
}
|
||||
void motor::Update()
|
||||
{
|
||||
//##########################
|
||||
// 사용자추가코드
|
||||
//##########################
|
||||
|
||||
if (var.pingtime == 0 || var.pingtime > millis()) var.pingtime = millis();
|
||||
long runtime = millis() - var.pingtime;
|
||||
|
||||
//중지조건 체크
|
||||
//(충전중, 비상정지, 오버로드, 설정화면)
|
||||
bool bStop1 = var.getFlag(FLAG_SETUP);
|
||||
bool bStop2L = bitRead(var.IOData, IDXI_OVERLOADL);
|
||||
bool bStop2R = bitRead(var.IOData, IDXI_OVERLOADR);
|
||||
bool bStop3 = bitRead(var.IOData, IDXI_EMG);
|
||||
bool bStop4 = bitRead(var.IOData, IDXI_STOP);
|
||||
|
||||
//중지조건이 활성화되었다면 처리
|
||||
String stpReason = "";
|
||||
|
||||
//Z축 중지는 오버로드만 확읺ㄴ다.
|
||||
if (bStop3== true)
|
||||
{
|
||||
if (var.getFlag(FLAG_STOPZ) == false)
|
||||
{
|
||||
dbgSerial.println("Set Flag On: flag_stopz by EMG");
|
||||
var.setFlag(FLAG_STOPZ, true, "MotUpdate");
|
||||
}
|
||||
}
|
||||
else if (bStop2L == true)
|
||||
{
|
||||
if (var.getFlag(FLAG_STOPZ) == false)
|
||||
{
|
||||
dbgSerial.println("Set Flag On: flag_stopz by OverloadL");
|
||||
var.setFlag(FLAG_STOPZ, true, "MotUpdate_OVLL");
|
||||
}
|
||||
}
|
||||
else if (bStop2R == true)
|
||||
{
|
||||
if (var.getFlag(FLAG_STOPZ) == false)
|
||||
{
|
||||
dbgSerial.println("Set Flag On: flag_stopz by OverloadR");
|
||||
var.setFlag(FLAG_STOPZ, true, "MotUpdate_OVLR");
|
||||
}
|
||||
}
|
||||
else if (var.getFlag(FLAG_STOPZ) == true)
|
||||
{
|
||||
dbgSerial.println("Set Flag Off");
|
||||
var.setFlag(FLAG_STOPZ, false, "MotUpdate");
|
||||
}
|
||||
|
||||
//가이드 모터 동작시 Limit 센서 체크
|
||||
ZLimit_AutoStop();
|
||||
|
||||
if (var.getFlag(FLAG_STOPZ) == true)
|
||||
{
|
||||
if (IsMoveZ() == true)
|
||||
{
|
||||
Serial.println("Z-Axis Auto Stop by 'STOP-Z' Condition");
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
}
|
||||
}
|
||||
|
||||
//Serial.println("motor update");
|
||||
}
|
||||
|
||||
|
||||
//Z축이 동작죽이라면 리밋센서값을 보고 자동으로 멈춥니다
|
||||
void motor::ZLimit_AutoStop()
|
||||
{
|
||||
if (mot.IsMoveZ() == true)
|
||||
{
|
||||
//정방향이동시(올라간다)
|
||||
if (mot.GetZDirL() == ZDIR_CW)
|
||||
{
|
||||
if (bitRead(var.IOData, IDXI_OVERLOADL) == true ) //오버로드 활성화시 멈춤
|
||||
{
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis Auto Stop by OverloadL", false);
|
||||
}
|
||||
else if (bitRead(var.IOData, IDXI_OVERLOADR) == true ) //오버로드 활성화시 멈춤
|
||||
{
|
||||
mot.SetZRun(ZRUN_STOP);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis Auto Stop by OverloadR", false);
|
||||
}
|
||||
else {
|
||||
//상단센서가 하나라도 동작하면 멈춘다
|
||||
if (mot.IsMoveZL() == true && bitRead(var.IOData, IDXI_LIMIT_LU) == true)
|
||||
{
|
||||
mot.SetZRunL(false);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis (Left) Auto Stop by Upper Limit", false);
|
||||
}
|
||||
if (mot.IsMoveZR() == true && bitRead(var.IOData, IDXI_LIMIT_RU) == true)
|
||||
{
|
||||
mot.SetZRunR(false);
|
||||
if (var.getFlag(FLAG_SETUP) == false)hmi.SendMessage("Z-Axis (Right) Auto Stop by Upper Limit", false);
|
||||
}
|
||||
}
|
||||
}
|
||||
else //역방향이동(내려간다)
|
||||
{
|
||||
//하단센서가 하나라도 동작하면 멈춘다
|
||||
if (mot.IsMoveZL() == true && bitRead(var.IOData, IDXI_LIMIT_LD) == true)
|
||||
{
|
||||
mot.SetZRunL(false);
|
||||
if (var.getFlag(FLAG_SETUP) == false)hmi.SendMessage("Z-Axis (Left) Auto Stop by Lower Limit", false);
|
||||
}
|
||||
if (mot.IsMoveZR() == true && bitRead(var.IOData, IDXI_LIMIT_RD) == true)
|
||||
{
|
||||
mot.SetZRunR(false);
|
||||
if (var.getFlag(FLAG_SETUP) == false)hmi.SendMessage("Z-Axis (Right) Auto Stop by Lower Limit", false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
//가이드 모터 진행방향을 반환(CW:Up, CCW:Down)
|
||||
ZDirection motor::GetZDirL()
|
||||
{
|
||||
bool value = bitRead(var.IOData, IDXO_GUIDEMOTOR_LDIR + 16);
|
||||
if (value == false) return ZDIR_CW;
|
||||
else return ZDIR_CCW;
|
||||
}
|
||||
ZDirection motor::GetZDirR()
|
||||
{
|
||||
bool value = bitRead(var.IOData, IDXO_GUIDEMOTOR_RDIR + 16);
|
||||
if (value == false) return ZDIR_CW;
|
||||
else return ZDIR_CCW;
|
||||
}
|
||||
|
||||
//가이드 모터(좌+우) 동작 여부
|
||||
bool motor::IsMoveZ()
|
||||
{
|
||||
if (IsMoveZL() == true) return true;
|
||||
else if (IsMoveZR() == true) return true;
|
||||
else return false;
|
||||
}
|
||||
|
||||
//가이드 모터(좌) 동작 여부
|
||||
bool motor::IsMoveZL()
|
||||
{
|
||||
bool v1 = bitRead(var.IOData, IDXO_GUIDEMOTOR_LRUN + 16);
|
||||
//bool v2 = bitRead(var.IOData, IDXO_GUIDEMOTOR_LEFT + 16);
|
||||
return v1 ;
|
||||
}
|
||||
|
||||
//가이드 모터(우) 동작 여부
|
||||
bool motor::IsMoveZR()
|
||||
{
|
||||
bool v1 = bitRead(var.IOData, IDXO_GUIDEMOTOR_RRUN + 16);
|
||||
//bool v2 = bitRead(var.IOData, IDXO_GUIDEMOTOR_RIGHT + 16);
|
||||
return v1 ;
|
||||
}
|
||||
|
||||
//가이드모터 진행방향 결정(True:정방향, False:역방향)
|
||||
void motor::SetZDir(ZDirection direction)
|
||||
{
|
||||
if (direction == ZDIR_CW) {
|
||||
digitalWrite(PINO_GUIDEMOTOR_LDIR, LOW);
|
||||
digitalWrite(PINO_GUIDEMOTOR_RDIR, LOW);
|
||||
}
|
||||
else {
|
||||
digitalWrite(PINO_GUIDEMOTOR_LDIR, HIGH);
|
||||
digitalWrite(PINO_GUIDEMOTOR_RDIR, HIGH);
|
||||
}
|
||||
}
|
||||
|
||||
void motor::SetZRun(ZRunMode runMode) {
|
||||
|
||||
bool bEmg = var.getFlag(FLAG_STOPZ); //Z축이 움직이면 안되는 조건이므로 처리하지 않는다.
|
||||
|
||||
if (runMode == ZRUN_UP)
|
||||
{
|
||||
if (bEmg) {
|
||||
hmi.SendMessage("[Ignore] Z-Run by Stop-Z Flag", true);
|
||||
return;
|
||||
}
|
||||
SetZDir(ZDIR_CW);
|
||||
SetZRunL(true);
|
||||
SetZRunR(true);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Guide Up", false);
|
||||
}
|
||||
else if (runMode == ZRUN_DN)
|
||||
{
|
||||
if (bEmg) {
|
||||
hmi.SendMessage("[Ignore] Run by Stop-Z Flag", true);
|
||||
return;
|
||||
}
|
||||
SetZDir(ZDIR_CCW);
|
||||
SetZRunL(true);
|
||||
SetZRunR(true);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Guide Dn", false);
|
||||
}
|
||||
else if (runMode == ZRUN_STOP)
|
||||
{
|
||||
SetZRunL(false);
|
||||
SetZRunR(false);
|
||||
if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Guid Stop", false);
|
||||
//digitalWrite(PINO_GUIDEMOTOR_RUN, LOW);
|
||||
}
|
||||
}
|
||||
|
||||
void motor::SetZRunL(bool run) {
|
||||
if (run == true)
|
||||
{
|
||||
//if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis Left Run", false);
|
||||
digitalWrite(PINO_GUIDEMOTOR_LRUN, HIGH);
|
||||
//digitalWrite(PINO_GUIDEMOTOR_RUN, HIGH);
|
||||
}
|
||||
else {
|
||||
digitalWrite(PINO_GUIDEMOTOR_LRUN, LOW);
|
||||
//L,R둘다 꺼져있다면 STA도 끈다
|
||||
//if (bitRead(var.IOData, IDXO_GUIDEMOTOR_RIGHT + 16) == false)
|
||||
//{
|
||||
// if (var.getFlag(FLAG_SETUP) == false)hmi.SendMessage("Z-Axis Sta Off by Right", false);
|
||||
// digitalWrite(PINO_GUIDEMOTOR_RUN, LOW);
|
||||
//}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void motor::SetZRunR(bool run) {
|
||||
if (run == true)
|
||||
{
|
||||
//if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis Right Run", false);
|
||||
digitalWrite(PINO_GUIDEMOTOR_RRUN, HIGH);
|
||||
//digitalWrite(PINO_GUIDEMOTOR_RUN, HIGH);
|
||||
}
|
||||
else {
|
||||
digitalWrite(PINO_GUIDEMOTOR_RRUN, LOW);
|
||||
//L,R둘다 꺼져있다면 STA도 끈다
|
||||
//if (bitRead(var.IOData, IDXO_GUIDEMOTOR_LEFT + 16) == false)
|
||||
//{
|
||||
// if (var.getFlag(FLAG_SETUP) == false) hmi.SendMessage("Z-Axis Sta Off by Right", false);
|
||||
// digitalWrite(PINO_GUIDEMOTOR_RUN, LOW);
|
||||
//}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
motor mot;
|
||||
52
Arduino_PLC/motor.h
Normal file
52
Arduino_PLC/motor.h
Normal file
@@ -0,0 +1,52 @@
|
||||
#ifndef _MOTOR_H_
|
||||
#define _MOTOR_H_
|
||||
#include "arduino.h"
|
||||
#include "VarClass.h"
|
||||
|
||||
enum ZRunMode
|
||||
{
|
||||
ZRUN_STOP = 0,
|
||||
ZRUN_UP,
|
||||
ZRUN_DN
|
||||
};
|
||||
enum ZDirection
|
||||
{
|
||||
ZDIR_CW = 0,
|
||||
ZDIR_CCW
|
||||
};
|
||||
|
||||
class motor {
|
||||
|
||||
public:
|
||||
|
||||
void Setup();
|
||||
void Update();
|
||||
|
||||
void SetSpeedZ(uint8_t value);
|
||||
|
||||
ZDirection GetZDirL(); //Z축 진행방향을 표시합니다. True 일경우, 정방향(위로), False일경우 역방향(아래로)
|
||||
ZDirection GetZDirR(); //Z축 진행방향을 표시합니다. True 일경우, 정방향(위로), False일경우 역방향(아래로)
|
||||
void SetZDir(ZDirection direction); //1=정방향, 0=역방향
|
||||
|
||||
void SetZRun(ZRunMode run);
|
||||
void SetZRunL(bool run);
|
||||
void SetZRunR(bool run);
|
||||
|
||||
|
||||
bool IsMoveZ(); //현재 이동중인가?
|
||||
|
||||
private:
|
||||
|
||||
void SetPowerL(bool on);
|
||||
void SetPowerR(bool on);
|
||||
|
||||
bool IsMoveZL();
|
||||
bool IsMoveZR();
|
||||
|
||||
void ZLimit_AutoStop(); //Z축 리밋센서에 의한 동작 정지
|
||||
|
||||
};
|
||||
|
||||
extern motor mot;
|
||||
|
||||
#endif
|
||||
Reference in New Issue
Block a user