task main() { nNxtButtonTask = -2; nxtDisplayCenteredTextLine(0, "Codatex"); nxtDisplayCenteredBigTextLine(1, "RFID"); nxtDisplayCenteredTextLine(3, "Test 1"); nxtDisplayCenteredTextLine(5, "Connect sensor"); nxtDisplayCenteredTextLine(6, "to S1"); wait1Msec(2000); eraseDisplay(); nxtDisplayCenteredTextLine(3, "Start single"); nxtDisplayCenteredTextLine(4, "reading loop"); wait1Msec(2000); eraseDisplay(); // loop for transponder readings in single read mode while(nNxtButtonPressed == kNoButton) { // read the transponder, if no mode (single/continuous) has been // set, it will default to single shotting the sensor. if (!CTRFIDreadTransponder(CTRFID, transponderID)) { eraseDisplay(); nxtDisplayTextLine(3, "Error reading"); nxtDisplayTextLine(4, "from sensor!"); wait10Msec(5000); StopAllTasks(); } nxtDisplayCenteredTextLine(3, "Transponder ID:"); nxtDisplayCenteredTextLine(4, "%s", transponderID); // Be sure to add about 200ms after each read // or you end up getting 0000000000 as a transponder address wait1Msec(200); } }
task main() { nNxtButtonTask = -2; nxtDisplayCenteredTextLine(0, "Codatex"); nxtDisplayCenteredBigTextLine(1, "RFID"); nxtDisplayCenteredTextLine(3, "Test 2"); nxtDisplayCenteredTextLine(5, "Connect sensor"); nxtDisplayCenteredTextLine(6, "to S1"); wait1Msec(2000); eraseDisplay(); nxtDisplayCenteredTextLine(3, "Start single"); nxtDisplayCenteredTextLine(4, "reading loop"); wait1Msec(2000); eraseDisplay(); // Set up the sensor for continuous readings. CTRFIDsetContinuous(CTRFID); // loop for transponder readings with continuous read function while(nNxtButtonPressed == kNoButton) { // read the transponder if (!CTRFIDreadTransponder(CTRFID, transponderID)) { eraseDisplay(); nxtDisplayTextLine(3, "Error reading"); nxtDisplayTextLine(4, "from sensor!"); wait10Msec(5000); StopAllTasks(); } nxtDisplayCenteredTextLine(3, "Transponder ID:"); nxtDisplayCenteredTextLine(4, "%s", transponderID); // Be sure to add about 200ms after each read // or you end up getting 0000000000 as a transponder address wait1Msec(200); } }