Marc Bax
/
EtonBreadboard_090
main.cpp
- Committer:
- marcbax
- Date:
- 2011-03-28
- Revision:
- 0:fd45411cac49
File content as of revision 0:fd45411cac49:
//Firmware to drive Eton bee trainer breadboard char* fwversion = "0.90"; //For published versions use format "n.nn" //For development versions add "D" to end of string //This version published on 28/03/2011 //Include libraries #include "mbed.h" #include "Servo.h" //need this library to control servos //Pin assignments and external functions DigitalOut led1(LED1), led2(LED2), led3(LED3), led4(LED4); //for debugging purposes only DigitalOut buzzer(p5); //pin high means buzzer on DigitalOut airswitcher(p7); //pin high shorts coax for air switcher valve Serial display(p9,p10); //serial display controller by ByVAC BV4618 controller AnalogOut irLED(p18); //only one analog out controls both IR LEDS in parallel AnalogIn ptor1(p19), ptor2(p20); //analog input for beeholder phototransistors Servo arm1(p21), elbow1(p22); //servos for station 1 robot arm Servo arm2(p23), elbow2(p24); //servos for station 2 robot arm I2C beeholder(p28,p27); //set up I2C communication to read beeholder serial no DigitalOut bhsel1(p29), bhsel2(p30); //select lines for station 1 and station 2 - pull low to select holder DigitalIn upsw(p13), risw(p14), dnsw(p15), lesw(p16), oksw(p17); //footswitch connected parallel to OK switch LocalFileSystem local("local"); //allow access to the mbed "thumbdrive" as a file system FILE *logfile = fopen("/local/etonlog.csv","w"); //creates new file etonlog.csv and set for writing. Overwrites existing file! //Definition of global constants //station 1 (left) robot arm positions float arm1basepos = 0.4; float elbow1basepos = 0.07; float arm1dippos = 0.2; float elbow1dippos = 0.6; float arm1ticklepos = 0.65; float elbow1ticklepos = 0.07; float arm1feedpos = 0.7; float elbow1feedpos = 0.4; //station 2 (right) robot arm positions float arm2basepos = 0.4; float elbow2basepos = 0.07; float arm2dippos = 0.2; float elbow2dippos = 0.07; float arm2ticklepos = 0.2; float elbow2ticklepos = 0.07; float arm2feedpos = 0.2; float elbow2feedpos = 0.07; //robot arm hold and move times all times are in seconds float diptime = 1; //time that brush stays down dipped in sugar water float tickletimeout = 3; //maximum time to tickle if no PER is detected float feedtime = 3; //feeding time //PER detection parameters float calsetval = 1.4; //voltage to which phototransistor output will be calibrated float PERsetval = 2.1; //phototransistor output needs to be above this voltage for PER float PERtime = 0.2; //phototransistor output needs to stay high this long in seconds //I2C address int addr = 0xA2; //address is actually 0x51, but mbed expects left-shifted address //Definition of global variables struct holderrecord { //used to hold data on beeholder int serialno; //beeholder serial number 0-9999 float calvalue; //IR-LED calibration value char cycleno; //number of cycles gone through in this session char reslastcycle; //result of last cycle, 1 for PER char ticklenextcycle; //whether tickling was done for last cycle time_t tstamp; //timestamp when last cycle was run }; holderrecord currentholder; //struct record for the current beeholder holderrecord sessionrecord[30]; //sessionrecord contains holderrecords for up to 30 beeholders int numbeeholders; //number of beeholders used in current session int station; //which station is used in this session //Substance strings struct submenuitem { char* displaystring; //keep display string to 19 characters or less, otherwise display screws up char* logstring; //this is the string that gets printed in the logfile, and can be longer then 19 characters }; submenuitem submenu[11]; int substanceindex; //this variable contains the index number (in the list) of the selected substance //Function declarations //Short beep void beeponce() { buzzer = 1; wait(0.1); buzzer = 0; } //beep beep beep void multibeeps(int number, float interval) { for(int i=0;i<number;i++){ beeponce(); wait(interval); } } //Clears and homes the display void cleardisplay() { display.printf("\e[2J\e[H"); } //Returns both robot arms to base position void armstobase() { elbow1 = elbow1basepos; elbow2 = elbow2basepos; wait(0.5); //need this delay to avoid snagging brush on IR LED arm1 = arm1basepos; arm2 = arm2basepos; } //Fills the substance menu array with text void fillsubstancemenu() { submenu[0].displaystring = "No substance"; submenu[0].logstring = "Lack of substance"; submenu[1].displaystring = "Coffee"; submenu[1].logstring = "Espresso macchiato"; submenu[2].displaystring = "Earl Grey"; submenu[2].logstring = "Nice cup of tea"; submenu[3].displaystring = "Apple Pie"; submenu[3].logstring = "Mom's homemade apple pie - longer then 19 characters"; submenu[4].displaystring = "Substance 04"; submenu[4].logstring = "Substance 4"; submenu[5].displaystring = "Substance 05"; submenu[5].logstring = "Substance 5"; submenu[6].displaystring = "Substance 06"; submenu[6].logstring = "Substance 6"; submenu[7].displaystring = "Substance 07"; submenu[7].logstring = "Substance 7"; submenu[8].displaystring = "Substance 08"; submenu[8].logstring = "Substance 8"; submenu[9].displaystring = "Substance 09"; submenu[9].logstring = "Substance 9"; submenu[10].displaystring = "Red Roses"; submenu[10].logstring = "I never promised you a rose garden"; } //Initialises sessionrecords void sessionrecordinit() { for (int i=0; i<30; i++) { //set base values for all possible beeholders sessionrecord[i].serialno = 0; //set serialno to 0 so we can detect a unresponsive holder sessionrecord[i].calvalue = 0; sessionrecord[i].cycleno = 0; sessionrecord[i].reslastcycle = 0; sessionrecord[i].ticklenextcycle = 1; //default is to tickle on each cycle } } //Initialisation on power-on void initialise() { //Set pins to a defined state led1 = led2 = led3 = led4 =0; //internal LEDs only used for debugging purposes buzzer = 0; //buzzer off airswitcher = 0; //relay contacts open, clean air position bhsel1 = bhsel2 = 1; //I2C select lines high to deselect both beeholders upsw.mode(PullUp); //set pull-up on all frontpanel switches risw.mode(PullUp); dnsw.mode(PullUp); lesw.mode(PullUp); oksw.mode(PullUp); //Set robot arms to base positions armstobase(); //initialise the display display.baud(19200); //set display baud rate to 19200 display.putc(0x0d); //send CR to display - this needs to be first character sent after power-up wait(0.5); //wait for display to adjust to serial baud rate display.printf("\e[4L\e[20c"); //set display to 4 lines of 20 characters cleardisplay(); //clear screen and home cursor //display splash screen with time display.printf("Eton trainer v%s\r", fwversion); //show firmware release version time_t seconds = time(NULL); //creates timestamp char bufferd[20], buffert[20]; strftime(bufferd, 20, "%d/%m/%Y", localtime(&seconds)); //formats date part of timestamp display.printf("Date: %s\r", bufferd); //displays date strftime(buffert, 20, "%X", localtime(&seconds)); //formats time part of timestamp display.printf("Time: %s\r", buffert); //displays time wait(3); //display splash screen cleardisplay(); //clear screen and home cursor //initialise sessionrecord sessionrecordinit(); //initialise substance menu fillsubstancemenu(); //enter info in logfile.csv fprintf(logfile, "%s\r", bufferd); //writes date, time and firmware version fprintf(logfile, "%s\r", buffert); fprintf(logfile, "v%s\r", fwversion); beeponce(); //three beeps to signal initialisation ready } //Returns the index of the selected substance menu item int subchoice(submenuitem submenu[11]) { bool up, down, done; int i; up = down = done = 0; i = 0; cleardisplay(); display.printf("Substance selection"); wait(3); cleardisplay(); while (!done) { display.printf("%s\r", submenu[i].displaystring); display.printf("\rUP/DOWN to scroll\rOK to select"); while (!up && !down && !done) { up = !upsw; down = !dnsw; done = !oksw; } if (up) { i++; if (i==11) i = 0; } if (down) { if (i==0) i = 11; i--; } cleardisplay(); } return i; } //Converts the last 4 digits in the serial number string into a integer 0-9999 int serialstring2int(char bser[8]) { int tempserial = 0; tempserial = tempserial + (bser[4]-0x30)*1000; //5th digit is thousands tempserial = tempserial + (bser[5]-0x30)*100; //6th digit is hundreds tempserial = tempserial + (bser[6]-0x30)*10; //7th digit is tens tempserial = tempserial + (bser[7]-0x30); //8th digit is units return tempserial; } //beeholder resets on rising edge of select line void resetbeeholder() { //need this as mounting beeholder causes undefined start of beeholder firmware bhsel1 = bhsel2 = 0; wait(0.1); bhsel1 = bhsel2 = 1; wait(0.3); } //Reads beeholder serial number from station 1 or 2 int getserialno(int station) { char bser[8]; //define 8-byte serial number string to read resetbeeholder(); //does not work without this!! for (int i=0;i<8;i++) bser[i]=0x30; if (station==1) bhsel1=0; //pull select line station 1 low if (station==2) bhsel2=0; //pull select line station 2 low wait(0.2); beeholder.stop(); //I2C stop condition wait(0.2); //delay for beeholder to respond beeholder.write(addr,0x0,1); //initial write before read beeholder.read(addr,bser,8); //read 8 byte serial number bhsel1 = bhsel2= 1; //pull both select lines high int serialno = serialstring2int(bser); //translate serial number string to integer return serialno; } //Returns 1 if a PER is detected on this beeholder within timeout seconds int detectPER(int station, float timeout) { Timer ttotal, tper; ttotal.start(); //start timers for time-out and PER-detect ttotal.reset(); tper.start(); tper.reset(); if (station == 1) { while ((ttotal.read() < timeout) && (tper.read() < PERtime)) { //loop until timeout or PER detected wait_ms(10); if (ptor1 * 3.3 < PERsetval) tper.reset(); //if phototransistor voltage below treshold keep PER timer in reset //if above treshold let timer run until it reaches PERtime } } if (station == 2) { while ((ttotal.read() < timeout) && (tper.read() < PERtime)) { if (ptor2 * 3.3 < PERsetval) tper.reset(); } } ttotal.stop(); tper.stop(); return (tper.read() >= PERtime); //if the loop exit condition was a PER, return a TRUE value } //Checks if bee shows PER when stimulated with odour but without feeding int checktrained(int station) { airswitcher = 1; int responded = detectPER(station, 6); //PER needs to be detected within 6 seconds airswitcher = 0; return responded; } //Function performs beeholder/IR-led calibration float calibrate(int station, int runs) { float tempcal; tempcal=0.5; //start calibration at 50% voltage irLED=tempcal; float calstep; //start calstep at 25% voltage calstep = tempcal/2; for (int i=0; i<10; i++) { //does a "10-bit binary search" for the correct voltage to get a good response irLED = tempcal; wait(0.1); //important to allow AD converter to settle if (ptor1 < calsetval/3.3) { //check phototransistor voltage against desired value tempcal = tempcal - calstep; //if phototransistor voltage is too low then reduce brightness } else { tempcal = tempcal + calstep; //if phototransistor voltage is too high then increase brightness } calstep = calstep/2; //on each loop of the for-cycle make smaller changes to IR LED voltage } float calib; calib = tempcal; //set preliminary calibration to the value just measured for (int j=1; j<runs; j++) { //run another j-1 runs, this corrects for antennae-movement as tempcal=0.5; //we use the lowest calibration value from j runs irLED=tempcal; //this is similar to what we do in the cassettes calstep = tempcal/2; for (int i=0;i<10;i++) { irLED = tempcal; wait(0.1); if (ptor1 < calsetval/3.3) { tempcal = tempcal - calstep; } else { tempcal = tempcal + calstep; } calstep = calstep/2; } if (tempcal < calib) calib = tempcal; //use the lowest of j calibration values } return calib; } //switches the IR LED on at the right brightness level for the beeholder void IRledON(int i) { irLED = sessionrecord[i].calvalue; } //moves arm1 to a position in a specified time, allowing speed control void arm1move (float endpos, float movetime) { float startpos = arm1.read(); int numsteps = (movetime * 50); //50 pulses/second, so each step is 1 servo pulse for (int i=0; i<numsteps; i++) { arm1 = startpos + i * (endpos - startpos)/numsteps; wait(movetime/numsteps); } arm1 = endpos; } //moves arm2 to a position in a specified time, allowing speed control void arm2move (float endpos, float movetime) { float startpos = arm2.read(); int numsteps = (movetime * 50); //50 pulses/second, so each step is 1 servo pulse for (int i=0; i<numsteps; i++) { arm2 = startpos + i * (endpos - startpos)/numsteps; wait(movetime/numsteps); } arm2 = endpos; } //moves elbow1 to a position in a specified time, allowing speed control void elbow1move (float endpos, float movetime) { float startpos = elbow1.read(); int numsteps = (movetime * 50); //50 pulses/second, so each step is 1 servo pulse for (int i=0; i<numsteps; i++) { elbow1 = startpos + i * (endpos - startpos)/numsteps; wait(movetime/numsteps); } elbow1 = endpos; } //moves elbow2 to a position in a specified time, allowing speed control void elbow2move (float endpos, float movetime) { float startpos = elbow2.read(); int numsteps = (movetime * 50); //50 pulses/second, so each step is 1 servo pulse for (int i=0; i<numsteps; i++) { elbow2 = startpos + i * (endpos - startpos)/numsteps; wait(movetime/numsteps); } elbow2 = endpos; } //Performs a conditioning cycle. if tickle==0, no tickling takes place. Return==1 if a PER has been detected int condcycle(int station, int tickle) { int perseen; perseen = 0; //for station 1 if (station == 1) { //dip brush arm1move(arm1dippos, 0.5); elbow1move(elbow1dippos, 0.3); wait(diptime); elbow1move(elbow1basepos, 0.3); arm1move(arm1basepos, 0.5); //switch air to supply trace vapour airswitcher = 1; //air contains target vapour display.printf("Vapour ON"); wait (0.5); //tickle if (tickle) { //if tickling, first tickle then wait for PER or timeout elbow1move(elbow1ticklepos, 0.2); arm1move(arm1ticklepos, 1.5); //slower move of arm towards bee perseen = detectPER(1, tickletimeout); //tickle until timeout or PER detected } //or not tickle else { perseen = detectPER(1, tickletimeout); //if not tickling, wait for PER or timeout then move to pre-feeding position arm1move(arm1ticklepos-0.05, 1); //move to position between LED and holder elbow1move(elbow1ticklepos, 0.3); } //feeding only if you have tickled or a PER has been detected if (tickle || perseen) { //only feed if a PER has been detector, or "tickle" is true elbow1move(elbow1feedpos, 0.3); arm1move(arm1feedpos, 0.3); wait(feedtime); arm1move(arm1ticklepos -0.05, 0.3); elbow1move(elbow1ticklepos, 0.3); } //move back to base position arm1 = arm1basepos; //use fast move here elbow1 = elbow1basepos; //use fast move here airswitcher = 0; //air valve to clean air display.printf("\e[DFF\r"); //rewrite "ON" to "OFF" on display } //for station 2 if (station == 2) { //dip brush arm2move(arm2dippos, 0.5); elbow2move(elbow2dippos, 0.3); wait(diptime); elbow2move(elbow2basepos, 0.3); arm2move(arm2basepos, 0.5); //switch air to supply trace vapour //airswitcher = 1; //no air switching for station 2 wait (0.5); //tickle if (tickle) { //if tickling, first tickle then wait for PER or timeout elbow2move(elbow2ticklepos, 0.2); arm2move(arm2ticklepos, 1.5); //slower move of arm towards bee perseen = detectPER(1, tickletimeout); //tickle until timeout or PER detected } //or not tickle else { perseen = detectPER(1, tickletimeout); //if not tickling, wait for PER or timeout then move to pre-feeding position arm2move(arm2ticklepos-0.05, 1); //move to position between LED and holder elbow2move(elbow2ticklepos, 0.3); } //feeding only if you have tickled or a PER has been detected if (tickle || perseen) { //only feed if a PER has been detector, or "tickle" is true elbow2move(elbow2feedpos, 0.3); arm2move(arm2feedpos, 0.3); wait(feedtime); arm2move(arm2ticklepos -0.05, 0.3); elbow2move(elbow2ticklepos, 0.3); } //move back to base position arm2 = arm2basepos; elbow2 = elbow2basepos; } return perseen; } //User to input choice between station 1 and 2 for this session int stationchoice() { int station; station = 1; cleardisplay(); //clear screen and home cursor display.printf(" Station selection "); display.printf("Left=1 2=Right"); while (lesw && risw) { //lesw and risw become false when pressed! wait(0.02); if (!lesw) station=1; //on LEFT select station 1 if (!risw) station=2; //on RIGHT select station 2 } display.printf("\rStation %1u selected", station); fprintf(logfile, "%3u, station selected\r", station); return station; } //Registers and calibrates all beeholders used in this session int registerbeeholders() { int i; bool done; char buffert[30]; i = done = 0; cleardisplay(); //clear screen and home cursor fprintf(logfile, "calibration record:\r"); fprintf(logfile, "i, serialno, LED V, time\r"); while (i<30 && !done) { //register and calibrate a maximum of 30 beeholders display.printf("calibrating %u\r",i+1); sessionrecord[i].serialno = getserialno(station); //read serial number if (sessionrecord[i].serialno != 0) { //check if serial number correctly read - if not it will be 0000 sessionrecord[i].calvalue = calibrate(station, 5); //5 calibration cycles if ((sessionrecord[i].calvalue > 0.25) && (sessionrecord[i].calvalue < 0.97)) { //check that calvalue is in expected range sessionrecord[i].tstamp = time(NULL); //create timestamp NOW strftime(buffert, 20, "%X", localtime(&sessionrecord[i].tstamp)); //formats time part of timestamp cleardisplay(); display.printf("SN %4u - cal %4.2fV\r", sessionrecord[i].serialno, sessionrecord[i].calvalue*3.3); display.printf("OK for next\r"); display.printf("DOWN for training"); fprintf(logfile, "%4u,%6u,%6.2f, %s, calibrate\r", i, sessionrecord[i].serialno, sessionrecord[i].calvalue*3.3, buffert); i++; } else { cleardisplay(); display.printf("SN %4u - cal %4.2fV\r", sessionrecord[i].serialno, sessionrecord[i].calvalue*3.3); display.printf("Cal out of range!\r"); multibeeps(2,0.5); display.printf("OK to recalibrate\r"); fprintf(logfile, "%4u,%6u,%6.2f, %s, out of range\r", i, sessionrecord[i].serialno, sessionrecord[i].calvalue*3.3, buffert); } while (!done && oksw) { //loop until OK or DOWN are pressed wait(0.02); done = !dnsw; //DOWN exits registration cycle and moves to training } } else { //retry when serialno can't be read (is 0000) cleardisplay(); multibeeps(3,0.3); //beep-beep-beep when beeholder not correctly read display.printf("invalid serial no\r"); display.printf("reseat beeholder\r"); display.printf("press OK"); while (oksw) wait(0.02); //loop until OK is pressed to start calibration loop again } cleardisplay(); } return i; //upon done condition, i== number of beeholders calibrated } //gets holderrecord for the holder with a certain serial number int getholderindex(int serialno) { for (int i=0; i<numbeeholders; i++) { //reverse lookup of index for a certain serial number if (sessionrecord[i].serialno == serialno) return i; } return 29; //if the record is not found, returns i==29 } //all the elements making up a single training cycle with one beeholder void trainingcycle() { wait(0.2); time_t tstamp = time(NULL); //create timestamp NOW char buffert[30]; strftime(buffert, 20, "%X", localtime(&tstamp)); //format timestamp to time string bool invalidserial; invalidserial = 1; int serialno; serialno = 0; while (invalidserial) { //loop until a serial number is read correctly cleardisplay(); int serialno = getserialno(station); //read serial number invalidserial = (serialno == 0); //if the serialno is 0, then it's invalid if (invalidserial) { display.printf("Invalid serialno\rReseat holder\rUP to retry"); while (upsw) wait(0.02); //loop until UP switch is pressed } } int i = getholderindex(serialno); //get index i for serial number IRledON(i); //switch IR LED on at correct brightness sessionrecord[i].cycleno++; //increment cycle number for this beeholder cleardisplay(); display.printf("SN: %4u, cycle %u\r", serialno, sessionrecord[i].cycleno); sessionrecord[i].reslastcycle = condcycle(station, sessionrecord[i].ticklenextcycle); //do a conditioning cycle fprintf(logfile, "%s,",buffert); fprintf(logfile, " %4u,",serialno); fprintf(logfile, " %2u,", sessionrecord[i].cycleno); if (sessionrecord[i].reslastcycle) { //log PER or TimeOut fprintf(logfile, " PER,"); } else { fprintf(logfile, " TO,"); } fprintf(logfile, " training\r"); if (sessionrecord[i].reslastcycle) { display.printf("PER detected\r"); } else { display.printf("PER time-out\r"); } display.printf("mount holder + OK\r"); display.printf("DOWN to finish"); } //main program int main() { initialise(); //initialise a new session //Choose which station this session will use station = stationchoice (); //menu to let user select station 1 or 2 cleardisplay(); //Choose substance string substanceindex = subchoice(submenu); //menu to let use chose substance fprintf(logfile, "%s\r", submenu[substanceindex].logstring); //prints the substance log string to the logfile //Register and calibrate beeholders used in this session display.printf("Now register holders\r"); display.printf("seat first holder\rpress OK\r"); while (oksw) wait(0.02); //loop so first beeholder can be mounted, then OK pressed numbeeholders = registerbeeholders(); display.printf("%2u holders entered\r", numbeeholders); wait(3); cleardisplay(); //Conduct training display.printf("Start training cycle\r"); display.printf("mount holder + OK\r"); display.printf("DOWN to finish"); fprintf(logfile, "Training started\r"); fprintf(logfile, "time, serial, cycleno, result\r"); wait(1); InterruptIn oksw(p17); //redefine OK and footswitch as interrupts oksw.mode(PullUp); bool finishsession; finishsession = 0; oksw.fall(&trainingcycle); //call subroutine "trainingcycle" on OK/footswitch interrupt while (!finishsession) { //loop while servicing interrupts wait(0.02); finishsession = !dnsw; //until DOWN button is pressed, which exits to program close } //Close logfile fprintf(logfile, "session closed"); fclose(logfile); //close logfile for reading cleardisplay(); display.printf("Session finished\r\rdownload etonlog.csvand rename"); }