#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#include <EEPROM.h>
LiquidCrystal_I2C lcd(0x27, 16, 2);// tinkercad, wokwi
//LiquidCrystal_I2C lcd(0x20, 16, 2); // proteus
//LiquidCrystal_I2C lcd(0x3E, 16, 2);
//LiquidCrystal_I2C lcd(0x3F, 16, 2); //my lcd
///////////////pin constant//////////////
int prevButton = 4;
int nextButton = 0;
int selectButton = 2;
int backButton = 15;
int buzPin = 17;
int xj1 = 13;
int yj1 = 12;
int yj2 = 14;
int xj2 = 27;
int pot1Pin = 26;
int pot2Pin = 25;
int Aux1Pin = 33;
int Aux2Pin = 32;
int vbatPin = 35;
//int ppmPin = 1;
/*{"Display", "Auto Calibrate", "Mode Setting", "Chanel Reverse","Sub Trim","End Point", "Dead Zone", "Curve Setting", "Reset"};
{"Dis(1000-2000)","Dis(0%-100%)","Dis (Raw Data)"};
{"Max Point", "Mid Point", "Min Point"};
{"Mode","Mixing"};{"channel 1","channel 2","channel 3",
{"Throttle Curve" ,"Pitch Curve"};
{"No", "Yes"}; */
bool showLevel1 = 0;
bool showLevel2 = 0;
bool showLevel3 = 0;
bool showLevel4 = 0;
int level1Item = 1;
int level2Item = 2;
int level3Item = 3;
int level4Item = 4;
int caseNo = 0;
bool ppm=0;
int page=1;
int display=1;
float voltage=0;
//////////////transmitter param//////////////////////////
int chmid[4] = {2048,2048,2048,2048}; //working value
int chval[8] = {2048,2048,0,2048,0,0,0,0};
int chmin[8] = {0,0,0,0,0,0,0,0};
int chmax[8] = {4095,4095,4095,4095,4095,4095,4095,4095};
bool reverse[8] = {0,0,0,0,0,0,0,0};
int dzone[4] = {0,0,0,0};
int mode = 2;
int rchmid[4] = {127,127,127,127}; /////reset value
int rchmin[8] = {0,0,0,0,0,0,0,0};
int rchmax[8] = {255,255,255,255,255,255,1,1};
bool rreverse[8]= {0,0,0,0,0,0,0,0};
int rdzone[4] = {0,0,0,0};
int rmode = 2;
////////eeprom address////////////////////////////////
int reverseAddr[8] = {0,1,2,3,4,5,6,7};
int midAddr[4] = {8,9,10,11};
int minAddr[4] = {12,13,14,15};
int maxAddr[4] = {16,17,18,19};
int dzAddr[4] = {20,21,22,23};
int modeAddr = 24;
int rollPin;
int pitchPin;
int throttlePin;
int yawPin;
void setup() {
///////////pin state //////////////
lcd.init();
lcd.backlight();
pinMode(prevButton, INPUT_PULLUP);
pinMode(nextButton, INPUT_PULLUP);
pinMode(selectButton, INPUT_PULLUP);
pinMode(backButton, INPUT_PULLUP);
pinMode(buzPin, OUTPUT);
//pinMode(ppmPin, OUTPUT);
/////////setup for transmitter//////////////
Serial.begin(9600);
lcd.setCursor(0, 0);
lcd.print(" WELCOME:");
//epromRead();
setMode();
int i=0;
while(i<5){
digitalWrite(buzPin,1);
delay(200);
digitalWrite(buzPin,0);
i++;
}
if(ppm==0){
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("Transmitter");
}
else{
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("PPM OUT");
}
delay(1000);
pageDisplay();
}
//////////////loop////////////////////////////
void loop() {
while(ppm>0){
//setupPPM();
checkPage();
checkLong();
chanRead();
dataConvert();
transmit();
if(showLevel1==1){break;}
}
while(ppm<1){
checkPage();
checkLong();
chanRead();
dataConvert();
transmit();
if(showLevel1==1){break;}
}
while(showLevel1 >0){
int lastCaseNo=caseNo;
checkButton();
if(lastCaseNo!=caseNo){
lcd.clear();
updateMenu();
}
}
if(ppm==0){
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("Transmitter");
}
else{
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("PPM OUT");
}
delay(1000);
pageDisplay();
}
/////////////////////////////////////////////
void pageDisplay(){
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("Ch");
lcd.print(2*page-1);
lcd.print("-");
lcd.setCursor(11, 0);
lcd.print("Vol ");
lcd.setCursor(15, 0);
if(ppm==1){lcd.print("S");}
else{lcd.print("N");}
lcd.setCursor(0, 1);
lcd.print("Ch");
lcd.print(2*page);
lcd.print("-");
}
void chanRead(){
chval[0] = analogRead(rollPin); //Roll
chval[1] = analogRead(pitchPin); //pitch
chval[2] = analogRead(throttlePin); //Throttle
chval[3] = analogRead(yawPin); //Yaw
chval[4] = analogRead(pot1Pin);
chval[5] = analogRead(pot2Pin);
chval[6] = analogRead(Aux1Pin);
chval[7] = analogRead(Aux2Pin);
chval[8] = analogRead(vbatPin);
for(int x=0; x<8; x++){
if(reverse[x]==1){
chval[x]=4096-chval[x];
}
}
}
void checkPage(){ ////////////pages for data
int prvpage=page;
if(!digitalRead(nextButton)){
while(!digitalRead(nextButton));
page++;
if(page==5){page=1;}
}
else if(!digitalRead(prevButton)){
while(!digitalRead(prevButton));
page--;
if(page==0){page=4;}
}
//constrain(page, 1, 4);
if(page!=prvpage){
pageDisplay();
}
}
void dataConvert(){
voltage=chval[8]*3.3*3.64/4095;
if(display==1){
for(int x=0; x<8 ; x++){
if(x<2 or x==3){
if(chval[x]<chmid[x]){chval[x]=map(chval[x],chmin[x],chmid[x]-dzone[x],1000,1500);}
else if(chval[x]>chmid[x]){chval[x]=map(chval[x],chmid[x]+dzone[x],chmax[x],1500,2000);}
else {chval[x]=1500;}
}
else if(x==2 or x>3){
chval[x]=map(chval[x],chmin[x],chmax[x],1000,2000);
}
}
}
else if(display==2){
for(int x=0; x<2 ; x++){
if(x<2 or x==3){
if(chval[x]<=chmid[x]){chval[x]=map(chval[x],chmin[x],chmid[x]-dzone[x],0,50);}
else if(chval[x]>=chmid[x]){chval[x]=map(chval[x],chmid[x]+dzone[x],chmax[x],50,100);}
else {chval[x]=50;}
}
else if(x==2 or x>3){
chval[x]=map(chval[x],chmin[x],chmax[x],0,100);
}
}
}
}
void checkLong(){
int pressTime=0;
int releseTime=0;
if (!digitalRead(selectButton)){
digitalWrite(buzPin,1);
pressTime=millis();
while(!digitalRead(selectButton));
releseTime=millis();
digitalWrite(buzPin,0);
if (showLevel1==0 && releseTime-pressTime>1500){showLevel1=1;}
}
}
void checkButton(){
/////////////select button press///////////////
if (!digitalRead(selectButton)){
digitalWrite(buzPin,1);
delay(50);
digitalWrite(buzPin,0);
if(showLevel2==0){showLevel2=1;}
else if(showLevel3==0){showLevel3=1;}
else if(showLevel4==0 && showLevel3==1){showLevel4=1;}
while(!digitalRead(selectButton));
}
///////////////////back button press////////////////
if (!digitalRead(backButton)){
digitalWrite(buzPin,1);
delay(50);
digitalWrite(buzPin,0);
if(showLevel4==1){
showLevel4=0;
}
else if(showLevel3==1){
showLevel3=0;
}
else if(showLevel2==1){
showLevel2=0;
}
else if(showLevel1==1){
showLevel1=0;
level1Item=1;
level2Item=2;
level3Item=3;
askTosave();
}
while(!digitalRead(backButton));
}
////////////next button next button/////////////////
if (!digitalRead(nextButton)){
digitalWrite(buzPin,1);
delay(50);
digitalWrite(buzPin,0);
if(showLevel3==1){level3Item++;}
else if(showLevel2==1){level2Item++;}
else if(showLevel1==1){level1Item++;}
while(!digitalRead(nextButton));
}
////////////previus button previus button/////////////////
if (!digitalRead(prevButton)){
digitalWrite(buzPin,1);
delay(50);
digitalWrite(buzPin,0);
if(showLevel3==1){level3Item--;}
else if(showLevel2==1){level2Item--;}
else if(showLevel1==1){level1Item--;}
while(!digitalRead(prevButton));
}
caseNo = showLevel1 * level1Item + 10 * showLevel2 * level2Item + 100 * showLevel3 * level3Item + 1000 * showLevel4 * level4Item ;
Serial.println(caseNo);
delay(100);
}
void updateMenu() {
chanRead();
dataConvert();
switch (caseNo) {
case 0:
if(showLevel1==1){level1Item=9;}
break;
case 1:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Display");
break;
case 2:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Auto Calibration");
break;
case 3:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Mode Setting");
break;
case 4:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Channel Reverse");
break;
case 5:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Sub Trim");
break;
case 6:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">End Point");
break;
case 7:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Dead Zone");
break;
case 8:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Curves Setting");
break;
case 9:
lcd.setCursor(0, 0);
lcd.print(" Menu List");
lcd.setCursor(0, 1);
lcd.print(">Factory Reset");
break;
case 10:
level1Item=1;
break;
/////////////////////display format////////////////////
case 11:
level2Item=4;
break;
case 21:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Display");
lcd.setCursor(0, 1);
lcd.print(">Dis:(1000-2000)");
if(display==1){
lcd.setCursor(15, 1);
lcd.print("*");
}
break;
case 31:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Display");
lcd.setCursor(0, 1);
lcd.print(">Dis: (0%-100%)");
if(display==2){
lcd.setCursor(15, 1);
lcd.print("*");
}
break;
case 41:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Display");
lcd.setCursor(0, 1);
lcd.print(">Dis: (Raw)");
if(display==3){
lcd.setCursor(15, 1);
lcd.print("*");
}
break;
case 51:
level2Item=2;
break;
///////////////////////Auto Calibration //////////
case 22:
autoCalib();
showLevel2=0;
break;
//////////////////////Mode Setting////////////
case 13:
level2Item=4;
break;
case 23:
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Select Mode");
break;
case 33:
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Mixing");
break;
case 43:
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">PPM Simulation");
if(ppm==1){
lcd.setCursor(15, 1);
lcd.print("*");
}
break;
case 53:
level2Item=2;
break;
/////////////////////Channel Reverse/////////////
case 14:
level2Item=9;
break;
case 24:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 1");
lcd.setCursor(15, 1);
lcd.print(reverse[0]);
break;
case 34:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 2");
lcd.setCursor(15, 1);
lcd.print(reverse[1]);
break;
case 44:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 3");
lcd.setCursor(15, 1);
lcd.print(reverse[2]);
break;
case 54:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 4");
lcd.setCursor(15, 1);
lcd.print(reverse[3]);
break;
case 64:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 5");
lcd.setCursor(15, 1);
lcd.print(reverse[4]);
break;
case 74:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 6");
lcd.setCursor(15, 1);
lcd.print(reverse[5]);
break;
case 84:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 7");
lcd.setCursor(15, 1);
lcd.print(reverse[6]);
break;
case 94:
lcd.setCursor(0, 0);
lcd.print("channel Reverse");
lcd.setCursor(0, 1);
lcd.print(">Channel: 8");
lcd.setCursor(15, 1);
lcd.print(reverse[7]);
break;
case 104:
level2Item=2;
break;
////////////////////Sub Trim/////////////////////
case 15:
level2Item=4;
break;
case 25:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Trim Point");
lcd.setCursor(0, 1);
lcd.print(">Ch:1 ");
break;
case 35:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Trim Point");
lcd.setCursor(0, 1);
lcd.print(">Ch:2 ");
break;
case 45:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Trim Point");
lcd.setCursor(0, 1);
lcd.print(">Ch:4 ");
break;
case 55:
level2Item=2;
break;
////////////////////End Point////////////////////
case 16:
level2Item=9;
break;
case 26:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:1");
break;
case 36:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:2");
break;
case 46:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:3");
break;
case 56:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:4");
break;
case 66:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:5");
break;
case 76:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:6");
break;
case 86:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:7");
break;
case 96:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" End Point Set");
lcd.setCursor(0, 1);
lcd.print(">Channel:8");
break;
case 106:
level2Item=2;
break;
////////////////////Dead Zone////////////////////
case 17:
level2Item=4;
break;
case 27:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" DZ Setting");
lcd.setCursor(0, 1);
lcd.print(">Ch:1 ");
lcd.setCursor(14, 1);
lcd.print(dzone[0]);
lcd.print(" ");
break;
case 37:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" DZ Setting");
lcd.setCursor(0, 1);
lcd.print(">Ch:2 ");
lcd.setCursor(14, 1);
lcd.print(dzone[1]);
lcd.print(" ");
break;
case 47:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" DZ Setting");
lcd.setCursor(0, 1);
lcd.print(">Ch:4 ");
lcd.setCursor(14, 1);
lcd.print(dzone[3]);
lcd.print(" ");
break;
case 57:
level2Item=2;
break;
////////////////////Curve////////////////////////
case 18:
level2Item=3;
break;
case 28:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Curve Setting");
lcd.setCursor(0, 1);
lcd.print(">Throttle Curve");
break;
case 38:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Curve Setting");
lcd.setCursor(0, 1);
lcd.print(">Other Curves");
break;
case 48:
level2Item=2;
break;
////////////////////Reset///////////////////////
case 19:
level2Item=3;
break;
case 29:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Factory Reset");
lcd.setCursor(0, 1);
lcd.print(">No");
break;
case 39:
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Factory Reset");
lcd.setCursor(0, 1);
lcd.print(">Yes");
break;
case 49:
level2Item=2;
break;
/////////////////////////////////////3rd level////////////////////
case 321:
display=1;
showLevel3=0;
break;
case 331:
display=2;
showLevel3=0;
break;
case 341:
display=3;
showLevel3=0;
break;
//////////////////////////Auto Clibration/////////
/////////////////////////mode setting////////////
case 223:
level3Item=6;
break;
case 323:
//lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Mode 1");
if(mode==1){
lcd.setCursor(12, 1);
lcd.print("*");
}
break;
case 423:
//lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Mode 2");
if(mode==2){
lcd.setCursor(12, 1);
lcd.print("*");
}
break;
case 523:
//lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Mode 3");
if(mode==3){
lcd.setCursor(12, 1);
lcd.print("*");
}
break;
case 623:
//lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Mode Setting");
lcd.setCursor(0, 1);
lcd.print(">Mode 4");
if(mode==4){
lcd.setCursor(12, 1);
lcd.print("*");
}
break;
case 723:
level3Item=3;
break;
//////////////////////////mixing///////////////
case 333:
showLevel3=0;
break;
/////////////////////////ppm simulation////////
case 343:
ppm=!ppm;
showLevel3=0;
showLevel2=0;
break;
////////////////reverse///////////////////
case 324:
reverse[0]=!reverse[0];
showLevel3=0;
break;
case 334:
reverse[1]=!reverse[1];
showLevel3=0;
break;
case 344:
reverse[2]=!reverse[2];
showLevel3=0;
break;
case 354:
reverse[3]=!reverse[3];
showLevel3=0;
break;
case 364:
reverse[4]=!reverse[4];
showLevel3=0;
break;
case 374:
reverse[5]=!reverse[5];
showLevel3=0;
break;
case 384:
reverse[6]=!reverse[6];
showLevel3=0;
break;
case 394:
reverse[7]=!reverse[7];
showLevel3=0;
break;
/////////////////////trim/////////////
case 325:
trim(1); ///ch 1
break;
case 335:
trim(2); ////ch 2
break;
case 345:
trim(4); ///ch 4
break;
/////////////////End Point//////////////
case 226:
level3Item=5;
break;
case 326:
lcd.setCursor(0, 0);
lcd.print(" Channel:1");
endDisplay(0);
break;
case 426:
lcd.setCursor(0, 0);
lcd.print(" Channel:1");
endDisplay(1);
break;
case 526:
lcd.setCursor(0, 0);
lcd.print(" Channel:1");
endDisplay(2);
break;
case 626:
level3Item=3;
break;
//////////////////
case 236:
level3Item=5;
break;
case 336:
lcd.setCursor(0, 0);
lcd.print(" Channel:2");
endDisplay(0);
break;
case 436:
lcd.setCursor(0, 0);
lcd.print(" Channel:2");
endDisplay(1);
break;
case 536:
lcd.setCursor(0, 0);
lcd.print(" Channel:2");
endDisplay(2);
break;
case 636:
level3Item=3;
break;
//////////////////
case 246:
level3Item=4;
break;
case 346:
lcd.setCursor(0, 0);
lcd.print(" Channel:3");
endDisplay(0);
break;
case 446:
lcd.setCursor(0, 0);
lcd.print(" Channel:3");
endDisplay(2);
break;
case 546:
level3Item=3;
break;
/////////////////////
case 256:
level3Item=5;
break;
case 356:
lcd.setCursor(0, 0);
lcd.print(" Channel:4");
endDisplay(0);
break;
case 456:
lcd.setCursor(0, 0);
lcd.print(" Channel:4");
endDisplay(1);
break;
case 556:
lcd.setCursor(0, 0);
lcd.print(" Channel:4");
endDisplay(2);
break;
case 656:
level3Item=3;
break;
////////////////
case 266:
level3Item=4;
break;
case 366:
lcd.setCursor(0, 0);
lcd.print(" Channel:5");
endDisplay(0);
break;
case 466:
lcd.setCursor(0, 0);
lcd.print(" Channel:5");
endDisplay(2);
break;
case 566:
level3Item=3;
break;
/////////////////////////
case 276:
level3Item=4;
break;
case 376:
lcd.setCursor(0, 0);
lcd.print(" Channel:6");
endDisplay(0);
break;
case 476:
lcd.setCursor(0, 0);
lcd.print(" Channel:6");
endDisplay(2);
break;
case 576:
level3Item=3;
break;
////////////////////
case 286:
level3Item=4;
break;
case 386:
lcd.setCursor(0, 0);
lcd.print(" Channel:7");
endDisplay(0);
break;
case 486:
lcd.setCursor(0, 0);
lcd.print(" Channel:7");
endDisplay(2);
break;
case 586:
level3Item=3;
break;
/////////////////////
case 296:
level3Item=4;
break;
case 396:
lcd.setCursor(0, 0);
lcd.print(" Channel:8");
endDisplay(0);
break;
case 496:
lcd.setCursor(0, 0);
lcd.print(" Channel:8");
endDisplay(2);
break;
case 596:
level3Item=3;
break;
////////////////Dead Zone///////////////
case 327:
DZSetting(1); ///ch 1
break;
case 337:
DZSetting(2); ////ch 2
break;
case 347:
DZSetting(4); ///ch 4
break;
/////////////////curve setting///////
case 328:
showLevel3=0;
break;
case 338:
showLevel3=0;
break;
///////////////reset/////////////////
case 329:
showLevel3=0;
showLevel2=0;
showLevel1=0;
showLevel4=0;
level1Item=1;
level2Item=2;
level3Item=3;
level4Item=4;
delay(100);
break;
case 339:
reset();
showLevel3=0;
showLevel2=0;
showLevel1=0;
showLevel4=0;
level1Item=1;
level2Item=2;
level3Item=3;
level4Item=4;
delay(100);
break;
////////////////level 4/////////////////////////
case 4323:
mode=1;
setMode();
showLevel4=0;
break;
case 4423:
mode=2;
setMode();
showLevel4=0;
break;
case 4523:
mode=3;
setMode();
showLevel4=0;
break;
case 4623:
mode=4;
setMode();
showLevel4=0;
break;
//////////////////////end point/////////
case 4326:
setEndpoint(1,0);
showLevel4=0;
break;
case 4426:
setEndpoint(1,1);
showLevel4=0;
break;
case 4526:
setEndpoint(1,2);
showLevel4=0;
break;
////////////////
case 4336:
setEndpoint(2,0);
showLevel4=0;
break;
case 4436:
setEndpoint(2,1);
showLevel4=0;
break;
case 4536:
setEndpoint(2,2);
showLevel4=0;
break;
/////////////////
case 4346:
setEndpoint(3,0);
showLevel4=0;
break;
case 4446:
setEndpoint(3,2);
showLevel4=0;
break;
///////////////////
case 4356:
setEndpoint(4,0);
showLevel4=0;
break;
case 4456:
setEndpoint(4,1);
showLevel4=0;
break;
case 4556:
setEndpoint(4,2);
showLevel4=0;
break;
//////////////////
case 4366:
setEndpoint(5,0);
showLevel4=0;
break;
case 4466:
setEndpoint(5,2);
showLevel4=0;
break;
////////////////////
case 4376:
setEndpoint(6,0);
showLevel4=0;
break;
case 4476:
setEndpoint(6,2);
showLevel4=0;
break;
//////////////////////
case 4386:
setEndpoint(7,0);
showLevel4=0;
break;
case 4486:
setEndpoint(7,2);
showLevel4=0;
break;
///////////////////
case 4396:
setEndpoint(8,0);
showLevel4=0;
break;
case 4496:
setEndpoint(8,2);
showLevel4=0;
break;
}
}
void endDisplay(int x){
if(x==0){
lcd.setCursor(0, 1);
lcd.print(">I");
lcd.setCursor(6, 1);
lcd.print(" M");
lcd.setCursor(13, 1);
lcd.print(" F");
}
else if(x==1) {
lcd.setCursor(0, 1);
lcd.print(" I");
lcd.setCursor(6, 1);
lcd.print(">M");
lcd.setCursor(13, 1);
lcd.print(" F");
}
else if(x==2) {
lcd.setCursor(0, 1);
lcd.print(" I");
lcd.setCursor(6, 1);
lcd.print(" M");
lcd.setCursor(13, 1);
lcd.print(">F");
}
}
void setEndpoint(int chn , int x){ /// x=I for Initial x=F for final value
lcd.clear();
lcd.setCursor(0, 0);
lcd.print("End Point Ch-");
lcd.print(chn);
lcd.setCursor(7, 1);
lcd.print("RVal-");
showLevel4=0;
while(1){
chanRead();
dataConvert();
if(!digitalRead(nextButton)){
if(x==0){chmin[chn-1]=chmin[chn-1]+5 ;}
else if(x==1){chmid[chn-1]=chmid[chn-1]+1 ;}
else if(x==2){chmax[chn-1]=chmax[chn-1]+5 ;}
while(!digitalRead(nextButton));
}
else if(!digitalRead(prevButton)){
if(x==0){chmin[chn-1]=chmin[chn-1]-5 ;}
else if(x==1){chmid[chn-1]=chmid[chn-1]-1 ;}
else if(x==2){chmax[chn-1]=chmax[chn-1]-5 ;}
}
//lcd.setCursor(0, 1);
//lcd.print(value[1]);
//lcd.print(" ");
lcd.setCursor(12, 1);
lcd.print(chval[chn-1]);
lcd.print(" ");
if(digitalRead(backButton)==0 or digitalRead(selectButton)==0){
delay(100);
break;
}
}
}
void reset(){
/////////////////reverse//////////
for(int x=0; x<8; x++){
EEPROM.write(reverseAddr[x], rreverse[x]);
}
////////////////mid value///////////////
for(int x=0; x<4; x++){
EEPROM.write(midAddr[x], rchmid[x]);
}
////////////////max value///////////////
for(int x=0; x<4; x++){
EEPROM.write(maxAddr[x], rchmax[x]);
}
////////////////min value///////////////
for(int x=0; x<4; x++){
EEPROM.write(minAddr[x], rchmin[x]);
}
////////////////dead Zone value///////////////
for(int x=0; x<4; x++){
EEPROM.write(dzAddr[x], rdzone[x]);
}
EEPROM.write(modeAddr, rmode);
}
void DZSetting(int x){
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" DZ Setting");
lcd.setCursor(0, 1);
lcd.print(">Ch:");
lcd.print(x);
lcd.print(" *");
showLevel3=0;
while(1){
chanRead();
dataConvert();
if(!digitalRead(nextButton)){
dzone[x-1]--;
while(!digitalRead(nextButton));
}
else if(!digitalRead(prevButton)){
dzone[x-1]++;
while(!digitalRead(prevButton));
}
dzone[x-1]=constrain(dzone[x-1], 0, 20);
lcd.setCursor(14, 1);
lcd.print(dzone[x-1]);
lcd.print(" ");
if(digitalRead(backButton)==0 or digitalRead(selectButton)==0){
delay(200);
break;
}
}
}
void trim(int x){
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(" Trim Point");
lcd.setCursor(0, 1);
lcd.print(">Ch:");
lcd.print(x);
lcd.print(" *");
showLevel3=0;
while(1){
chanRead();
dataConvert();
if(!digitalRead(nextButton)){
chmid[x-1]--;
while(!digitalRead(nextButton));
}
else if(!digitalRead(prevButton)){
chmid[x-1]++;
while(!digitalRead(prevButton));
}
lcd.setCursor(10, 1);
lcd.print(chval[x-1]);
if(digitalRead(backButton)==0 or digitalRead(selectButton)==0){
delay(200);
break;
}
}
}
void transmit(){
chanRead();
dataConvert();
lcd.setCursor(5, 0);
lcd.print(chval[page*2-2]);
lcd.print(" ");
lcd.setCursor(5,1);
lcd.print(chval[page*2-1]);
lcd.print(" ");
lcd.setCursor(11,1);
lcd.print(voltage);
lcd.print(" ");
}
void epromRead(){
for(int x=0; x<8; x++){
///////////reverse////////////////
reverse[x]=EEPROM.read(reverseAddr[x]);
}
////////////////mid value///////////////
for(int x=0; x<4; x++){
chmid[x]=4*EEPROM.read(midAddr[x]);
}
////////////////max value///////////////
for(int x=0; x<4; x++){
chmax[x]=4*EEPROM.read(maxAddr[x]);
}
////////////////min value///////////////
for(int x=0; x<4; x++){
chmin[x]=4*EEPROM.read(minAddr[x]);
}
////////////////dead Zone value///////////////
for(int x=0; x<4; x++){
dzone[x]=EEPROM.read(dzAddr[x]);
}
mode=EEPROM.read(modeAddr);
}
void save(){
for(int x=0; x<8; x++){
//EEPROM.update(reverseAddr[x], reverse[x]);
EEPUpdate(reverseAddr[x], reverse[x]);
}
////////////////mid value///////////////
for(int x=0; x<4; x++){
//EEPROM.update(midAddr[x], chmid[x]/4);
EEPUpdate(midAddr[x], chmid[x]/4);
}
////////////////max value///////////////
for(int x=0; x<4; x++){
//EEPROM.update(maxAddr[x], chmax[x]/4);
EEPUpdate(maxAddr[x], chmax[x]/4);
}
////////////////min value///////////////
for(int x=0; x<4; x++){
//EEPROM.update(minAddr[x], chmin[x]/4);
EEPUpdate(minAddr[x], chmin[x]/4);
}
////////////////dead Zone value///////////////
for(int x=0; x<4; x++){
//EEPROM.update(dzAddr[x], dzone[x]);
EEPUpdate(dzAddr[x], dzone[x]);
}
//EEPROM.update(modeAddr, mode);
EEPUpdate(modeAddr, mode);
}
void askTosave(){
lcd.clear();
lcd.setCursor(0,0);
lcd.print("To Exit- BackBtn");
lcd.setCursor(0,1);
lcd.print("To Save- SelcBtn");
while(1){
if(!digitalRead(backButton)){break;}
if(!digitalRead(selectButton)){
save();
break;}
}
}
void setMode(){
if(mode==1){
rollPin=xj1;
pitchPin=yj2;
throttlePin=yj1;
yawPin=xj2;
}
if(mode==2){
rollPin=xj1;
pitchPin=yj1;
throttlePin=yj2;
yawPin=xj2;
}
if(mode==3){
rollPin=xj2;
pitchPin=yj2;
throttlePin=yj1;
yawPin=xj1;
}
if(mode==4){
rollPin=xj2;
pitchPin=yj1;
throttlePin=yj2;
yawPin=xj1;
}
}
void EEPUpdate(int adr , int val){
if(EEPROM.read(adr)!=val){EEPROM.write(adr, val);}
}
void autoCalib(){
}