#include <OneWire.h>
#include <Wire.h>
#include <math.h>
#include <EEPROM.h>
#define IO_ADDR (0x70 >> 1) // adresa PCF8574 int ASCII_dec=0x30;// const ASCII
byte cyklus=0;
float sensorLight = 0; //def A1 int sensorLocation=0;//def A2 float sensorAkuCharging = 0;//def A3
int previousLocation;
byte lastLocation;
int speedRotate=255;
byte revolutionCounter;
bool startControl =false;
bool konec=false,konec2=false;
int STOPRight=0, STOPLeft=0;
bool pokus=true;
// inByte;
//A4 SDA //A5 SCL
//Pin0 Rx //Pin1 Tx
int DS18S20_Pin = 2; //DS18S20 Signal pin digital 2 OneWire ds(DS18S20_Pin);
//int sensorPosition1Switch_Pin; //zapínání kodér 1
int sensorPosition1Detect_Pin=3;
//int sensorPosition2Switch_Pin;//zapínání kodér 2 int sensorPosition2Detect_Pin=4;
//int sensorPosition3Switch_Pin;//zapínání kodér 4 int sensorPosition3Detect_Pin=5;
//int sensorPosition4Switch_Pin;//zapínání kodér 8 int sensorPosition4Detect_Pin=6;
int speedRotate_Pin=9;
int rightRotate_Pin=8;
int leftRotate_Pin=7;
int senzorintDistanceEcho_Pin=10; //vzdálenost int senzorintDistanceTrigr_Pin=11; //vzdálenost //int cameraSwitch_Pin=15;//zapínání kodér 16 //int IRlightSwitch_Pin=16;//zapínání kodér 32
/////////////////////////////////////// Orientation rotate ///////////////////////////////////////
void rotateRight() {
digitalWrite(rightRotate_Pin, LOW);// Vpravo maximalni rychlosti digitalWrite(leftRotate_Pin, HIGH);
analogWrite(speedRotate_Pin,255) ; }
void rotateLeft() {
digitalWrite(rightRotate_Pin, HIGH);// Vlevo maximalni rychlosti digitalWrite(leftRotate_Pin, LOW);
analogWrite(speedRotate_Pin,255) ;
}
void rotateRightvalue() {
digitalWrite(rightRotate_Pin, LOW);// Vpravo zadanou rychlosti digitalWrite(leftRotate_Pin, HIGH);
analogWrite(speedRotate_Pin,speedRotate) ; }
void rotateLeftvalue() {
digitalWrite(rightRotate_Pin, HIGH);// Vlevo zadanou rychlosti digitalWrite(leftRotate_Pin, LOW);
analogWrite(speedRotate_Pin,speedRotate) ; }
/////////////////////////////////////// Sensors functions ///////////////////////////////////////
float getDistance() {
digitalWrite(senzorintDistanceTrigr_Pin, LOW);
delayMicroseconds(2);
digitalWrite(senzorintDistanceTrigr_Pin, HIGH);
delayMicroseconds(10);
digitalWrite(senzorintDistanceTrigr_Pin, LOW);
float distance = pulseIn(senzorintDistanceEcho_Pin, HIGH);
distance= distance*0.017315f; //c = 331,8+0,61∙t return distance;
}
float getLight() {
sensorLight= analogRead(A1);
float light = 3621.5*(pow((sensorLight) * (5.0 / 1023.0),(-3.9)));
return light;
}
float getLocation() {
sensorLocation= analogRead(A2);
float location = sensorLocation * (5.0 / 1023.0);
return location;
}
float getAkuCharging() {
sensorAkuCharging =analogRead(A3);
float akuCharging = sensorAkuCharging * (5.0 / 1023.0);
return akuCharging;
}
float getTemp(){//vrati teplotu ve °C
byte data[12];
byte addr[8];
if (!ds.search(addr)) {
ds.reset_search();
return -1000; //kontroluje senzory v retezci }
ds.reset();
ds.select(addr); //
ds.write(0x44,1); // zahájí prevod dig. hodnoty
byte present = ds.reset();
ds.select(addr);
ds.write(0xBE); //
for (int i = 0; i < 9; i++) { // cyklus zapisujici 9 bitu data[i] = ds.read();
}
ds.reset_search();
byte MSB = data[1]; //zapsani nejvýznamnějšího a nejméněvyznamného bitu byte LSB = data[0];
float tempRead = ((MSB << 8) | LSB); //Dvojkový doplněk float TemperatureSum = tempRead / 16;
return TemperatureSum;
}
/////////////////////////////////////// Detect position ///////////////////////////////////////
void CheckRC() {
if(startControl ==true && revolutionCounter>=5) //&& inByte !=60) {
STOPRight=1;
digitalWrite(rightRotate_Pin, LOW);// STOP digitalWrite(leftRotate_Pin, LOW);
}
else{STOPRight=0;}
if(revolutionCounter<=1)//&& inByte !=62 ) {
STOPLeft=1;
digitalWrite(rightRotate_Pin, LOW);// STOP digitalWrite(leftRotate_Pin, LOW);
}
else{STOPLeft=0;}
}
void LocationRightself() {
while(konec2) {
preruseni();
LocationRight();
CheckRC();
} }
void LocationLeftself() {
while(konec2) {
preruseni();
LocationLeft();
CheckRC();
} }
void LocationRight()
{
preruseni();
cyklus ++;
sensorLocation = analogRead(A2); //senzor natoceni jednotlive polohy PIR delay(2);
if (cyklus==1){previousLocation=analogRead(A2);}
if (cyklus==2) {
if(lastLocation==4) {
if(sensorLocation-previousLocation < -20) // odečitani předchozi hodnoty cyklu průser poladit!!!!
{
EEPROM.write(0,1);
lastLocation=1;
//Serial.println("P1");
revolutionCounter++;
EEPROM.write(2,revolutionCounter);
delay(10);
} }
cyklus=0;
}
if (sensorLocation > 292 & sensorLocation < 295) {
EEPROM.write(0,2);
lastLocation=2;
//Serial.println("P2");
delay (20);
}
if (sensorLocation > 447 & sensorLocation < 450) {
EEPROM.write(0,3);
lastLocation=3;
//Serial.println("P3");
delay (20);
}
if (sensorLocation > 757 & sensorLocation < 760) {
EEPROM.write(0,4);
lastLocation=4;
// Serial.println("P4");
delay (20);
} }
void LocationLeft() {
preruseni();
cyklus++;
sensorLocation = analogRead(A2); //senzor natoceni jednotlive polohy PIR
if (cyklus==1){previousLocation=analogRead(A2);}
if (cyklus==2) {
if(lastLocation==2)//if (sensorLocation-previousLocation < -10 ) // odečitani předchozi hodnoty cyklu
{
if (sensorLocation-previousLocation < -10 ) //naprosto v pořádku {
EEPROM.write(0,1);
lastLocation=1;
// Serial.println("P1");
revolutionCounter--;
EEPROM.write(2,revolutionCounter);
delay(30);
} }
cyklus=0;
}
if (sensorLocation > 289 & sensorLocation < 292) {
EEPROM.write(0,2);
lastLocation=2;
// Serial.println("P2");
delay (20);
}
if (sensorLocation > 447 & sensorLocation < 450) {
EEPROM.write(0,3);
lastLocation=3;
// Serial.println("P3");
delay (20);
}
if (sensorLocation > 757 & sensorLocation < 760) {
EEPROM.write(0,4);
lastLocation=4;
// Serial.println("P4");
delay (20);
} }
///////////////////////////////////////Start sequence ///////////////////////////////////////
void start() {
//Serial.println("start");
startControl=false;
int escape=0;
delay(5);
Wire.beginTransmission(IO_ADDR);
delay(5);
Wire.write(escape);
delay(5);
Wire.endTransmission();
lastLocation=EEPROM.read(0); //nacteni posledni ulozene pozice revolutionCounter=EEPROM.read(2);
if (lastLocation>4) //osetreni podminky pri prvnim spusteni {
rotateRight();
while(lastLocation!=1) {
LocationRight();
}
revolutionCounter=3; //nastaveni poctu otacek v polovine dovoleneho rozsahu startControl=true;
analogWrite(speedRotate_Pin, 0) ; lastLocation=1;
}
if (lastLocation <=4 & revolutionCounter>3) {
/* digitalWrite(rightRotate_Pin, HIGH);// Vlevo maximalni rychlosti digitalWrite(leftRotate_Pin, LOW);
analogWrite(speedRotate_Pin,255);// speedRotate) ; */
rotateLeft();
while(revolutionCounter!=3) {
LocationLeft();
}
startControl =true;
analogWrite(speedRotate_Pin, 0);
lastLocation=1;
}
if (lastLocation <=4 & revolutionCounter<3) {
/* digitalWrite(rightRotate_Pin, LOW);// Vpravo maximalni rychlosti digitalWrite(leftRotate_Pin, HIGH); Proč to ksakru nejde?????
analogWrite(speedRotate_Pin,255);//speedRotate) ;*/
rotateRight();
while(revolutionCounter!=3) {
LocationRight();
}
startControl =true;
analogWrite(speedRotate_Pin, 0) ; lastLocation=1;
}
startControl =true;
}
///////////////////////////////////////Inter. sequence ///////////////////////////////////////
void preruseni() {
if ( startControl==true) {
CheckRC();
}
int inByte = Serial.read();
delay(5);
switch(inByte)
{ case 69: konec=false; selectControl();
break;
case 57: konec2=false;speedRotate=0;
break;
case 40: Serial.println(revolutionCounter);
break;
case 41: Serial.println(revolutionCounter);
break;
} }
////////////////////////////////////////////////////////////////Reset mC ///////////////////////////////////////////////////////////////////
void Reset()
{asm volatile(" jmp 0");}
////////////////////////////////////////////////////////////////Select Control ///////////////////////////////////////////////////////////////////
void selectControl() {//startControl
=true;//*********************************************************************SMAZAT pouze pro testování!!!
if (startControl==true & Serial.available() > 0) //po startovni sekvenci vyber modu {
char inSelectMode = Serial.read();
switch (inSelectMode) {
case 65: automaticMode();
break;
case 83: selfControl();
break;
} } }
void automaticMode() {
konec=true;
speedRotate=255;
Serial.println("Auto");
bool sensorPosition1, sensorPosition2, sensorPosition3, sensorPosition4;
int expanderWrite=64;
while(konec) {
while (expanderWrite>=64) {
int inByte = Serial.read();
switch(inByte) {
case 47:
int expanderRead10 =0; int expanderRead01=0 ; delay(5);
expanderRead10 = Serial.read() - ASCII_dec;
delay(5);
expanderRead01 = Serial.read() - ASCII_dec;
expanderWrite = expanderRead10 *10 + expanderRead01;
Wire.beginTransmission(IO_ADDR);
delay(5);
Wire.write(expanderWrite);
delay(5);
Wire.endTransmission();
sensorPosition1= expanderWrite % 2;
expanderWrite = expanderWrite / 2;
sensorPosition2= expanderWrite % 2;
expanderWrite = expanderWrite / 2;
sensorPosition3= expanderWrite % 2;
expanderWrite = expanderWrite / 2;
sensorPosition4= expanderWrite % 2;
delay(75000);//uklidnění senzorů }
}
if( digitalRead(sensorPosition1Detect_Pin)==LOW && sensorPosition1!=0) { Serial.println("DP1");
preruseni();
if (lastLocation==1){break;}
if((lastLocation==3 | lastLocation==4)&&lastLocation!=1 ) {preruseni();
if(revolutionCounter<5 && lastLocation!=1) {preruseni();
rotateRight();
while(lastLocation!=1) {
LocationRight();
preruseni();
}
lastLocation=1;
analogWrite(speedRotate_Pin, 0) ; delay(2000);
}
if(revolutionCounter>=5 && lastLocation!=1) {preruseni();
rotateLeft();
while(lastLocation!=1) {
LocationLeft();
preruseni();
}
lastLocation=1;
analogWrite(speedRotate_Pin, 0) ; delay(2000);preruseni();
} }
if((lastLocation=2 | sensorLocation <= 440)&&lastLocation!=1 ) {preruseni();
if(revolutionCounter>1 && lastLocation!=1) {preruseni();
rotateLeft();
while(lastLocation!=1) //|| pokus) {
LocationLeft();
preruseni();
delay(5);
}
lastLocation=1;
analogWrite(speedRotate_Pin, 0) ; delay(2000); preruseni();
}
if(revolutionCounter<=1 && lastLocation!=1) {preruseni();
rotateRight();
while(lastLocation!=1) {
LocationRight();
preruseni();
}
lastLocation=1;preruseni();
analogWrite(speedRotate_Pin, 0) ;preruseni();
delay(2000);
} } }
if( digitalRead(sensorPosition2Detect_Pin)==LOW && sensorPosition2!=0) { Serial.println("DP2");
preruseni();
if (lastLocation==2){break;}
if((lastLocation==4 | lastLocation==1 )&& lastLocation!=2) {preruseni();
if(revolutionCounter<5) {preruseni();
rotateRight();
while(lastLocation!=2) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ;preruseni();
delay(2000);
}
preruseni();
if(revolutionCounter>=5 && lastLocation!=2) {preruseni();
rotateLeft();
while(lastLocation!=2)
{
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ;preruseni();
delay(2000);
} }
if((lastLocation=3 | sensorLocation < 755 )&& lastLocation!=2) {preruseni();
if(revolutionCounter>1 && lastLocation!=2) {preruseni();
rotateLeft();
while(lastLocation!=2) {
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ;preruseni();
delay(2000);
}preruseni();
if(revolutionCounter<=1 && lastLocation!=2) {preruseni();
rotateRight();
while(lastLocation!=2) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ;preruseni();
delay(2000);
} } }
if( digitalRead(sensorPosition3Detect_Pin)==LOW && sensorPosition3!=0) { Serial.println("DP3");
preruseni();
if (lastLocation==3){break;}
if((lastLocation==1 | lastLocation==2) && lastLocation!=3) {preruseni();
if(revolutionCounter<5 && lastLocation!=3) {preruseni();
rotateRight();
while(lastLocation!=3) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
}
if(revolutionCounter>=5 && lastLocation!=3) {preruseni();
rotateLeft();
while(lastLocation!=3) {
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
} }
if(lastLocation=4 ) {preruseni();
if(revolutionCounter>1 && lastLocation!=3) {preruseni();
rotateLeft();
while(lastLocation!=3) {
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
}
if(revolutionCounter<=1) {preruseni();
rotateRight();
while(lastLocation!=3 && lastLocation!=3) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
}
} }
if( digitalRead(sensorPosition4Detect_Pin)==LOW && sensorPosition4!=0) { Serial.println("DP4");
preruseni();
if (lastLocation==4){break;}
if((lastLocation==2 | lastLocation==3) && lastLocation!=4) {preruseni();
if(revolutionCounter<5 && lastLocation!=4) {preruseni();
rotateRight();
while(lastLocation!=4) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
}
if(revolutionCounter>=5) {preruseni();
rotateLeft();
while(lastLocation!=4 && lastLocation!=4) {
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
} }
if(lastLocation=1 ) {preruseni();
if(revolutionCounter>1 && lastLocation!=4) {preruseni();
rotateLeft();
preruseni();
while(lastLocation!=4) {
LocationLeft();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);
}
if(revolutionCounter<=1) {preruseni();
rotateRight();
while(lastLocation!=4 && lastLocation!=4) {
LocationRight();
preruseni();
}
analogWrite(speedRotate_Pin, 0) ; preruseni();
delay(2000);preruseni();
} }
} }
selectControl();
}
void selfControl() { Serial.println("self");
konec =true;
float sensorTemperature = getTemp();// prichozi 0 v C# 1 pozor zmenit float sensorLight = getLight();// prichozi 1 v C# 2 pozor zmenit
float sensorLocation = getLocation(); //prichozi 2 v C# 9
float sensorAkuCharging = getAkuCharging();//prichozi 3 v C# 0 float sensorDistance = getDistance();//prichozi :
char inByte;
while(konec){
if(revolutionCounter>=5 && inByte !=60) {
STOPRight=1;
digitalWrite(rightRotate_Pin, LOW);// STOP digitalWrite(leftRotate_Pin, LOW);
}
else{STOPRight=0;}
if(revolutionCounter<=1 && inByte !=62) {
STOPLeft=1;
digitalWrite(rightRotate_Pin, LOW);// STOP digitalWrite(leftRotate_Pin, LOW);
}
else{STOPLeft=0;}
if (Serial.available() > 0) {
inByte = Serial.read();
//delay(5);
switch (inByte) {
case 47: // / a dvojice 00-32 nastavuje koder
int expanderRead10,expanderRead01 = 0, expanderWrite=0;
expanderRead10 = Serial.read()-ASCII_dec;
expanderRead01 = Serial.read()-ASCII_dec;
expanderWrite = expanderRead10 *10 + expanderRead01;
Wire.beginTransmission(IO_ADDR);
Wire.write(expanderWrite);
Wire.endTransmission();
break;
}
switch (inByte) {
case 40: Serial.println(revolutionCounter);
break;
case 41: Serial.println(revolutionCounter);
break;
case 48: Serial.println(sensorTemperature); //0 break;
case 49: Serial.println(sensorLight); //1 break;
case 50: Serial.println(sensorLocation);//2(sensorLocation);
break;
case 51: Serial.println(sensorAkuCharging);//3 break;
case 52: analogWrite(speedRotate_Pin, 158) ;//4 speedRotate=158;
break;
case 53: analogWrite(speedRotate_Pin, 178) ;//5 speedRotate=178;
break;
case 54: analogWrite(speedRotate_Pin, 200) ;//6 speedRotate=200;
break;
case 55: analogWrite(speedRotate_Pin, 220) ;//7 speedRotate=220;
break;
case 56: analogWrite(speedRotate_Pin, 255) ;//8 speedRotate=255;
break;
case 57: analogWrite(speedRotate_Pin, 0);
speedRotate=0;
konec2=false;//9 break;
case 58: Serial.println(sensorDistance);
break;
case 60: // digitalWrite(rightRotate_Pin, HIGH);// >
//digitalWrite(leftRotate_Pin, LOW);
rotateLeftvalue();
konec2=true;
LocationLeftself();
break;
case 62: //digitalWrite(rightRotate_Pin, LOW);//<
//digitalWrite(leftRotate_Pin, HIGH);
rotateRightvalue();
konec2=true;
LocationRightself();
break;
case 69: konec=false;
break;
case 82: Reset();
break;
}
}
}selectControl();
}
void setup(void) {
Serial.begin(9600);
Wire.begin();//inicializace expanderu
OneWire ds(DS18S20_Pin); // on digital pin 2 pinMode(sensorPosition1Detect_Pin, INPUT);
pinMode(sensorPosition2Detect_Pin, INPUT);
pinMode(sensorPosition3Detect_Pin, INPUT);
pinMode(sensorPosition4Detect_Pin,INPUT);
pinMode(speedRotate_Pin,OUTPUT);
pinMode(rightRotate_Pin,OUTPUT);
pinMode(leftRotate_Pin,OUTPUT);
pinMode(senzorintDistanceEcho_Pin,INPUT);
pinMode(senzorintDistanceTrigr_Pin,OUTPUT);
lastLocation=EEPROM.read(0);
revolutionCounter=EEPROM.read(2);
Serial.println(lastLocation);
Serial.println(revolutionCounter);
}
void loop(void) {
start();
selectControl();
}