/* Robot Ver 1.5 Dan Kohn 05/21/2011 */ //debug #define debug LOW //set HIGH for debug output //Define Pins #define LED 13 //if LED on solid - no remote control signal #define LED1 31 #define LED2 33 #define LED4 35 #define vex 10 #define sonar_init 52 #define sonar_echo 8 #define compass_in 9 #define m1_I1 7 #define m1_I2 6 #define m1_E 5 #define m2_I3 4 #define m2_I4 3 #define m2_E 2 #define m1_encoder 18 #define m2_encoder 19 #define m1_int 5 #define m2_int 4 //temp variables int temp; long temp2; //motor speed variables int m1_speed; int m2_speed; int speed; //motor encoder volatile unsigned long m1_count; volatile unsigned long m2_count; //vex RC variables long duration; long center=1040; //long span=350; long span=100; long q[7]; int mode; boolean button[4]; long ch5_last; long ch6_last; //sonar varialbes unsigned long starttime; unsigned long endtime; unsigned long ttime; float distance; //compass variable unsigned long compass; float bearing; //heading float bearing_target; float bearing_db; float bearing_h; float bearing_l; //mode 3 int direction; //autocalibration mode 4 int step; float point[100]; void setup() { // initialize the digital pin as an output. pinMode(LED, OUTPUT); pinMode(LED1, OUTPUT); pinMode(LED2, OUTPUT); pinMode(LED4, OUTPUT); //vex remote control reciever pinMode(vex, INPUT); mode=0; //H-bridge drive motor control pinMode(m2_E, OUTPUT); pinMode(m2_I4, OUTPUT); pinMode(m2_I3, OUTPUT); pinMode(m1_E, OUTPUT); pinMode(m1_I2, OUTPUT); pinMode(m1_I1, OUTPUT); //sonar pins pinMode (sonar_echo, INPUT); pinMode (sonar_init, OUTPUT); //compass pin pinMode (compass_in, INPUT); bearing_db=5; //encoder m1_count=0; m2_count=0; attachInterrupt(m1_int,encode_m1,RISING); attachInterrupt(m2_int,encode_m2,RISING); direction=0; step=0; Serial.begin(9600); } void loop() { digitalWrite(LED,LOW); // read vex remote control reciever and store values in q[chn#] noInterrupts(); do // wait for long sync pulse { duration = pulseIn(vex,LOW); if (duration ==0) //if no remote stop everything! { digitalWrite(LED,HIGH); digitalWrite(m2_E,LOW); digitalWrite(m1_E,LOW); } } while(duration < 7000); for (int x=1; x<=6; x++) // read 6 valid readings and store in q[1]..q[6] { duration=pulseIn(vex,LOW); q[x]=duration; } // handle chn5 and chn6 buttons (set variable button[] to true or false // and creates a mode number based on the binary value. // 2^3 is used as a clear bit for the other 3 bits. temp2=q[5]-ch5_last; if ((q[5]>1500)&&(abs(temp2)>50)) { button[2]=!button[2]; } else if ((q[5]<500)&&(abs(q[5]-ch5_last)>50)) { // button[3]=!button[3]; mode=0; button[0]=LOW; button[1]=LOW; button[2]=LOW; button[3]=LOW; } temp2=q[6]-ch6_last; if ((q[6]>1500)&&(abs(temp2)>50)) { button[1]=!button[1]; } else if ((q[6]<600)&&(abs(temp2)>50)) { button[0]=!button[0]; } mode=button[0]*1+button[1]*2+button[2]*4; digitalWrite(LED1,button[0]); digitalWrite(LED2,button[1]); digitalWrite(LED4,button[2]); ch5_last=q[5]; ch6_last=q[6]; interrupts(); //display reading from vex remote control if (debug) { for (int x=1; x<=6; x++) { Serial.print(x); Serial.print(":\t"); Serial.print(q[x]); Serial.print("\t"); } Serial.print(mode); Serial.print("\t"); } //sonar read and display digitalWrite(sonar_init,HIGH); starttime=micros(); delayMicroseconds(10); digitalWrite(sonar_init,LOW); do { }while(digitalRead(sonar_echo)!=HIGH); do { }while(digitalRead(sonar_echo)!=LOW); endtime=micros(); ttime=endtime-starttime; delay((25000-ttime)/1000); //make the sonar routine take a constant time to run distance=ttime*pow(10,-6)*1087*12/2; if (debug) { Serial.print(ttime); Serial.print(" "); Serial.print(distance); Serial.print("\t"); } //read and display compass compass = pulseIn(compass_in,HIGH); delay((36990-compass)/1000); //make this routine run in a constant time bearing = (compass-1000)/100; if (debug) { Serial.print(compass); Serial.print("\t"); Serial.print(bearing); Serial.print("\t"); } // //stop if no com with vex controller // if (q[1]<200 || q[1]>3000 || q[2]<200 || q[2]>3000 || q[3]<200 || q[3]>3000 || q[4]<200 || q[4]>3000 || q[5]<200 || q[5]>3000 || q[6]<200 || q[6]>3000) //check for dead remote and stop // { // Serial.print ("no remote"); // digitalWrite(m2_E,LOW); // digitalWrite(m1_E,LOW); // } if (mode==0) //Remote control drive { if (debug) { Serial.print("->"); Serial.print(speed); Serial.print("\t"); } if ((q[2]>center+span)&&(q[1]>center-span)&&(q[1]