#include "main.h" #include "states.c" main(){ xdata unsigned int test; UBYTE a, vl, vh; UINT voltage; long int timeout; // pause(1200); // initialization serial_init(); start_system_clock(); MOTOR = 1; // idle state, software UART STEERING_SERVO = 1; // idle state, software UART SOUND_MODULE = 1; // idle state, software UART STOP; PMR |= 0x01; // enable 1k RAM // send_to_camera('s'); obsticle_left = NO; obsticle_right = NO; obsticle_ahead = NO; reverse_attempts = 0; pause(1200); //#ifdef(1) //---- start of test code--------------------- //------------------------- //#endif // check for alternate program debug = NO; a = P0 & 0x0f; if (a == 15){ // debug mode debug = YES; CLEAR_DISPLAY sprintf(string, "debug mode...\0"); send_string(string); pause(500); } else if (a != 0) {select_alt_program();} // select alternate program // get and display battery voltage while(1){ voltage = get_battery_voltage(); CLEAR_DISPLAY // sprintf(string, "%4.1f Volts", voltage); // send_string(string); vh=voltage/10; vl=voltage%10; send_decimal_3(vh); send('.'); send(vl+0x30); timeout = current_time + 750; while(current_time < timeout AND NOT RIGHT_BUMPER); if(debug == NO OR RIGHT_BUMPER) {break;} } if(voltage < 124){say(WARNING_LOW_BATTERY); pause(3000);} else {say(IM_COMPLETELY_OPERATIONAL); pause(3000);} // allow the states to control the robot next_state = ASSESSMENT; // the first state to take control state_controller(); // handle the switching from one state to another // unused functions (prevents the linker from wasting RAM) is_bearing_within_range(1,1,1); } // end of main //-------------- void state_controller(void) { while(1){ // last_state = next_state; if(debug == YES){STOP while(NOT RIGHT_BUMPER);} // stop if in debug mode switch (next_state){ case ASSESSMENT: assessment(); break; case FORWARD: forward(); break; case CRUISE: cruise(); break; case VEER: veer(); break; case VEER_LEFT: veer_left(); break; case VEER_RIGHT: veer_right(); break; case SEMI_OPEN: semi_open(); break; case TOO_CLOSE: too_close(); break; case DEAD_END: dead_end(); break; case STUCK: stuck(); break; // case HALLWAY: hallway(); break; case FOLLOW_WALL: follow_wall();break; default:{ CLEAR_DISPLAY sprintf(string, "error-unknown state\0"); send_string(string); while(1); } } // end of switch statement } // end of loop } // end of function // --------------------------------------------- void look_left(void) { aim_sonar (2100, 25); // (far left) zone[1] = sonar() - SIDE_OFFSET; // send(0x03); send(0xc0); send_decimal_3 (distance_left); // display distance from sonar move_cursor(1,2); // 2nd line, 1st position send_decimal_3(zone[1]); SPACE send('c'); send('m'); } /*----------------------------*/ void look_right(void) { aim_sonar (1000, 25); zone[5] = sonar() - SIDE_OFFSET; // display distance from sonar move_cursor(14,2); // 2nd line, 14th position send_decimal_3(zone[5]); SPACE send('c'); send('m'); } /*----------------------------*/ /* void look_ahead(void) { aim_sonar (1600, 25); zone[3] = sonar() - FRONT_OFFSET; move_cursor(8,2); // send_decimal_3(zone[3]); send('c');send('m'); } */ /*----------------------------*/ void five_point_scan (void) { UBYTE n; UINT pulse[6] = {0,2400,2000,1600,1200,800}; // pulse[0] isn't used UBYTE offset[6]= {0,15,30,30,30,15}; // distance to edge of robot // zone direction pulse width // ---- ---------------- ---------- // 1 60 degrees left 2100 2400 // 2 30 degrees left 1900 2000 // 3 straight ahead 1600 1600 // 4 30 degrees right 1300 1200 // 5 60 degrees right 1100 800 move_cursor(1,2); aim_sonar (pulse[1],25); // get to the general area first for(n = 1; n <= 5; n++){ aim_sonar (pulse[n],8); zone[n] = sonar(); if(zone[n] > offset[n]){zone[n] -= offset[n];} else{zone[n] = 0;} send_decimal_3(zone[n]); SPACE } pause(100); } //------------------------------------ void move (int distance) { //stop and move forward or back-up for specified distance (cm) unsigned int a, c; unsigned long int time_limit; steer(STRAIGHT, 25); if (distance>0){motor_speed(40);} // 22 cm/s (1km/hr=27cm/s) else {motor_speed(-40);} aim_sonar(AHEAD, 25); time_limit = current_time + abs(distance) * 46; // 30=64cm, 42=80cm, 48=95cm while(current_time < time_limit){ check_distances(); if ( LEFT_BUMPER OR RIGHT_BUMPER ) {break;} if ( lw < 20 OR zone[3] < 20 OR lw < 20 ) {break;} } } //------------------------------ void turn_left(unsigned int degrees) { unsigned int a, c; unsigned long int time_limit; STOP steer(LEFT,25); motor_speed(40); aim_sonar(AHEAD,25); time_limit = current_time + (degrees * 60); while(current_time < time_limit){ //a = left_ir(); look_left(); c = right_ir(); // gather info check_distances(); if ( LEFT_BUMPER OR RIGHT_BUMPER ) {break;} if ( lw < 20 OR zone[3] < 20 OR rw < 20 ) {break;} } } /*----------------------------*/ void turn_right(unsigned int degrees) { unsigned int a, c; unsigned long int time_limit; STOP steer(RIGHT, 25); motor_speed(40); aim_sonar(AHEAD,25); time_limit = current_time + (degrees * 60); while(current_time < time_limit){ //a = left_ir(); look_right(); c = right_ir(); // gather info check_distances(); if ( LEFT_BUMPER OR RIGHT_BUMPER ) {break;} if ( lw < 20 OR zone[3] < 20 OR rw < 20 ) {break;} } } /*----------------------------*/ void reverse_left(void) { STOP pause(300); steer(RIGHT, 25); pause(500); motor_speed(-40); pause(1000); // STOP pause(200); } /*----------------------------*/ void reverse_right(void) { STOP pause(300); steer(LEFT, 25); pause(500); motor_speed(-40); pause(1000); //STOP pause(200); } /*-----------------------------*/ unsigned int bearing(void) { // 1-37ms = 0-360 degrees unsigned int degrees; unsigned int ticks; while (COMPASS_PULSE == 1); // if in the middle of a pulse, wait while (COMPASS_PULSE == 0); // wait for pulse to start TR0=0; TH0=0; TL0=0; // clear timer TMOD &= 0xf0; TMOD |= 0x01; // set up timer TR0=1; // start timer while (COMPASS_PULSE == 1); // wait for end of pulse TR0=0; // stop the timer ticks = TH0; ticks = (ticks << 8) + TL0; //send_decimal_3(TH0); //send(' '); //send_decimal_3(TL0); //send(' '); degrees = (ticks / 12 * 13 / 100) - 10; // send_decimal_3(degrees); return degrees; } // end of bearing //================================== /* * is_bearing_within_range * * Determine if the specified bearing (current) is within range (plus and minus * the specified delta around the base bearing. * * Parameters: * current (IN) - Current bearing * base (IN) - Base bearing * delta (IN) - Delta * * Returns: 1 if current bearing is within range, 0 otherwise. */ unsigned int is_bearing_within_range(unsigned int current, unsigned int base, unsigned int delta) { unsigned int min_bearing; unsigned int max_bearing; min_bearing = (base + 360 - delta) % 360; max_bearing = min_bearing + 2 * delta; if (min_bearing > current) { current += 360; } if (current >= min_bearing && current <= max_bearing) { return TRUE; } return FALSE; } /* is_bearing_within_range */ //--------------------------------------- void tone(UINT frequency, UINT duration) { UINT pulse; long int end_time = current_time + duration; pulse = 500000 / frequency; while(current_time < end_time){ PIEZO = LOW; set_timer(pulse); while (!TF0); PIEZO = HIGH; set_timer(pulse); while (!TF0); } } //--------------------------------------- void steer ( unsigned int position, unsigned int num ) // example: to move the steering a short distance to far left, // use "steer ( 600, 6 );" // 6 pulses will get the servo a short distance // 25 pulses is enough to get the servo anywhere { UBYTE a; // 9600 baud = 104.1us/bit // 1 tick = 1.085us // 104.1us = 96 ticks char n, b; TMOD &= 0xf0; TMOD |= 0x01; // set up timer a=position/10; // send start bit STEERING_SERVO = 0; WAIT_96 // send 8 data bits for(n=1; n<=8; n++){ b = a & 0x01; // b is the rightmost bit of a if (b == 1) {STEERING_SERVO = 1;} else {STEERING_SERVO = 0;} WAIT_96 a >>= 1; // next bit } // end for loop // send stop bit STEERING_SERVO = 1; WAIT_96 } /*----------------------------*/ unsigned int sonar(void) { unsigned int ticks, distance, a; ticks = 0; SONAR_START = 0; if(SONAR_RESULT == 1){ CLEAR_DISPLAY sprintf(string, "no response from sonar\0"); send_string(string); pause(2000); return(0); } SONAR_START = 1; // send ping set_timer(10); while (!TF0); // pause over 10us SONAR_START = 0; while (SONAR_RESULT == 0); // wait for pulse TR0=0; TF0=0; TH0=0; TL0=0; TR0=1; // clear and start timer while (SONAR_RESULT == 1); // wait for end of pulse TR0 = 0; ticks = TH0; ticks = (ticks << 8) + TL0; if (ticks > 16000 OR ticks < 0) { ticks = 16000; } // limit to 16,000 (304 cm) distance = ticks / 10 * 19 / 100; pause (10); // time between measurments return distance; } /*------------------------------*/ void aim_sonar ( unsigned int position, unsigned int num ) // example: to move the sensors a short distance to far left, // use "aim_sonar ( 1100, 6 );" // 25 pulses is enough to get the servo anywhere { unsigned int n; int a; TMOD &= 0xf0; TMOD |= 0x01; // set up timer for( n=0 ; n>8; TL0 = a%256; // set timer SENSOR_SERVO =1; // start the pulse TF0=0; // clear the timer flag TR0=1; // start timer while (!TF0); // wait for the timer flag SENSOR_SERVO=0; // end the pulse pause (20); } } /*----------------------------------*/ void motor_speed (unsigned char a) { // 9600 baud = 104.1us/bit // 1 tick = 1.085us // 104.1us = 96 ticks char n, b; TMOD &= 0xf0; TMOD |= 0x01; // set up timer // if(a>100){send('M');} // SBUF1 = a; // send start bit MOTOR = 0; WAIT_96 // send 8 data bits for(n=1; n<=8; n++){ b = a & 0x01; // b is the rightmost bit of a if (b == 1) {MOTOR = 1;} else {MOTOR = 0;} WAIT_96 a >>= 1; // next bit } // end for loop // send stop bit MOTOR = 1; WAIT_96 } // end function /*----------------------------------*/ unsigned int left_ir( ) // for the Sharp GP2D02 distance sensor { unsigned int distance = 0, a, b, c; unsigned char count; LEFT_IR_CONTROL = 0; // start pause(1); // start delay, 1ms (t1) was 2 while (LEFT_IR_DATA == 0); // wait while it measures (t2) // READ 8 BITS for ( count=1 ; count<=8 ; count++ ){ LEFT_IR_CONTROL = 1; set_timer(12); while(!TF0); // was 20 ,stay high for 20us (200us is max) LEFT_IR_CONTROL = 0; // request a bit set_timer(50); while(!TF0); // was 70 valid data delay (t5) distance *= 2; // shift left if (LEFT_IR_DATA == 1) { distance++;} } LEFT_IR_CONTROL = 1; pause (2); // intermeasurement delay (t6) // was 3 a = distance; b = 70; if(a>66){b=50;} if(a>68){b=48;} if(a>68){b=46;} if(a>69){b=44;} if(a>71){b=42;} if(a>74){b=40;} if(a>75){b=38;} if(a>78){b=36;} if(a>81){b=34;} if(a>83){b=32;} if(a>86){b=30;} if(a>91){b=28;} if(a>94){b=26;} if(a>99){b=24;} if(a>105){b=22;} if(a>112){b=20;} if(a>125){b=18;} if(a>130){b=16;} if(a>142){b=14;} if(a>160){b=12;} if(a>182){b=10;} c = b - 7; if(c < 0){c = 0;} return (c); } /*----------------------------*/ unsigned int right_ir( ) // for the Sharp GP2D02 distance sensor { unsigned int distance = 0, a, b, c; unsigned char count; RIGHT_IR_CONTROL = 0; // start pause(1); // start delay, 1ms (t1) while (RIGHT_IR_DATA == 0); // wait while it measures (t2) // read 8 bits for ( count=1 ; count<=8 ; count++ ) { RIGHT_IR_CONTROL = 1; set_timer(12); while(!TF0); // RIGHT_IR_CONTROL = 0; // request a bit set_timer(50); while(!TF0); // valid data delay (t5) distance = distance*2; // shift left if (RIGHT_IR_DATA == 1) { distance++;} } RIGHT_IR_CONTROL = 1; pause (2); // intermeasurement delay (t6) a = distance; b = 70; // convert value from module to cm if(a>99){b=50;} if(a>101){b=48;} if(a>102){b=46;} if(a>104){b=44;} if(a>105){b=42;} if(a>107){b=40;} if(a>109){b=38;} if(a>111){b=36;} if(a>114){b=34;} if(a>116){b=32;} if(a>119){b=30;} if(a>123){b=28;} if(a>127){b=26;} if(a>133){b=24;} if(a>137){b=22;} if(a>144){b=20;} if(a>153){b=18;} if(a>163){b=16;} if(a>176){b=14;} if(a>192){b=12;} if(a>215){b=10;} c = b - 7; if(c < 0){c = 0;} return (c); } /*----------------------------*/ void pause(unsigned int ms) { unsigned int count, n; // char temp; for (count=0; count < ms ; ++count ){ for(n=0;n<1245;++n){ } // 1 / 11,095,200 / ? // set_timer( 921 ); while (!TF0); // ( 1000 * 11.0952 / 12 ) } } /*---------------------------*/ void set_timer(unsigned int value) { unsigned int a; TR0=0; TMOD &= 0xf0; TMOD |= 0x01; // set up timer a = 0-(value); TH0 = a>>8; TL0 = a%256; TF0=0; // clear the timer flag TR0=1; // start timer } /*----------------------------*/ void serial_init(void) { // serial 0 init SM0 = 0; SM1 = 1; SM2 = 1; REN = 1; SCON = 0x50; // mode 1, 8-bit UART, enable rcvr TMOD &= 0x0f; TMOD |= 0x20; // timer 1, mode 2, 8-bit reload TH1 = 0xfd; // reload value for 9600 baud //TH1 = 0xfa; // reload value for 4800 baud //TH1 = 0xf4; // reload value for 2400 baud TR1 = 1; // timer 1 run TI = 1; // set TI to send first char of UART // serial 1 init SCON1 = 0x40; // set to 8-bit UART REN_1 = 1; // enable receiver } /*--------------------------------*/ void send(unsigned char a) { putchar(a); rf_putc(a); // send to rf module pause(10);// increased to keep the RF module from overloading // pause(2); } /*------------------------------------*/ void send_decimal_4(unsigned int a) { unsigned char thousands, hundreds, tens, ones; if (a>9999) {send('E'); pause(2000);} thousands = a / 1000; a = a - (thousands * 1000); hundreds = a / 100; a = a - (hundreds * 100); tens = a / 10; ones = a - (tens * 10); thousands = thousands + 0x30; // convert to text hundreds = hundreds + 0x30; // convert to text tens = tens + 0x30; // convert to text ones = ones + 0x30; // convert to text send(thousands); send(hundreds); send(tens); send(ones); } /*--------------------------------------*/ void send_decimal_3(signed int a) { unsigned char hundreds, tens, ones; if (a<0) {send('-'); return;} if (a>999) {send('>'); pause(2000);} hundreds = a / 100; a = a - (hundreds * 100); tens = a / 10; ones = a - (tens * 10); // convert to text hundreds = hundreds + 0x30; tens = tens + 0x30; ones = ones + 0x30; send(hundreds); send(tens); send(ones); } /*----------------------------------------*/ void start_system_clock(void) { unsigned int a, b; EA = 1; ET2 = 1; // enable interupts TR2 = 0; CP_RL2 = 0; C_T2 = 0; // set timer 2 to auto-reload timer mode b = 0 - 921; // (921 ticks = 1ms) RCAP2H = b >> 8; RCAP2L = b % 256; // set to overflow every ms current_time = 0; TF2 = 0; // clear the timer flag TR2 = 1; // start the timer } //------------------------------ void update_system_clock(void) interrupt 5 { current_time++; // increment TF2 = 0; // clear the flag } /*----------------------------*/ void send_string (unsigned char *string) { unsigned char i; for (i = 0; string[i] != '\0'; i++) { send ( string[i] ); } } //--------------------------------- /* void send_string_to_camera(unsigned char *string) { unsigned char i; for (i = 0; string[i] != '\0'; i++) { send_to_camera ( string[i] ); pause(30); // 10 doesnt work } } */ //--------------------------------- void rf_putc(char a) { TI_1 = 0; // clear flag SBUF1 = a;// send byte while(TI_1 == 0);// wait till finished } //--------------------------------- UBYTE rf_getc(void) // uses serial port 1 (the 2nd serial port) { UBYTE a; while(RI_1 == 0); // wait for receive flag a = SBUF1; RI_1 = 0; // clear the flag return(a); } //--------------------------------- void clear_obsticle_memory(void) { obsticle_left = NO; obsticle_right = NO; obsticle_ahead = NO; reverse_attempts = 0; P2=255; // LED's off } //--------------------------------- void check_distances(void) { int a; lw = left_ir(); rw = right_ir(); a = sonar(); if(a < 20){STOP say(THERES_SOMETHING_SCREWY);pause(3000);} zone[3] = a - FRONT_OFFSET; if(zone[3] < 0){zone[3] = 0;} // move_cursor(1,2); // begining of second line // sprintf(string,"3%d 3%d 3%d\0", lw, zone[3], rw); // send_string(string); move_cursor(1,2); // begining of second line send_decimal_3(lw); move_cursor(8,2); send_decimal_3(zone[3]); move_cursor(16,2); send_decimal_3(rw); } //--------------------------------- void move_cursor(char horiz, char vert) { unsigned char a; if(horiz < 1 OR horiz > 20 OR vert < 1 OR vert > 2){ CLEAR_DISPLAY sprintf(string, "cursor error\0"); send_string(string); while(1); } a = horiz + 0x7F; if(vert != 1) {a = a + 0x40;} send(0x03); // ^c makes the next byte an LCD command send(a); // cursor position code } //------------------------------------------- void say(int address) // plays a recorded sound starting at the specified address { sprintf(string, "sA%4xp", address); send_string_to_sound_module(string); // } //------------------------------------------- void send_string_to_sound_module(unsigned char *string) { unsigned char i; for (i = 0; string[i] != '\0'; i++) { send_to_sound_module ( string[i] ); pause(30); // 10 doesnt work (for camera) } } //---------------------------------------------- void send_to_sound_module(char a){ char n, b; TMOD &= 0xf0; TMOD |= 0x01; // set up timer // send start bit SOUND_MODULE = 0; WAIT_96 // send 8 data bits for(n=1; n<=8; n++){ b = a & 0x01; // b is the rightmost bit of a if (b == 1) {SOUND_MODULE = 1;} else {SOUND_MODULE = 0;} WAIT_96 a >>= 1; // next bit } // end for loop // send stop bit SOUND_MODULE = 1; WAIT_96 } //----------------------------------------- UBYTE get_battery_voltage(void){ UBYTE voltage, count, i; int v; v=0; for(i=1;i<100;i++){ voltage=0; if(BATTERY_INPUT == 0){pause(2);} // while(BATTERY_INPUT == 1); //wait for start bit pause(2); while(BATTERY_INPUT == 1); //wait for start bit // wait half a bit WAIT_48 // read 8 bits for ( count=1 ; count<=8 ; count++ ) { WAIT_96 // wait 1 bit voltage = voltage / 2; // shift left if (BATTERY_INPUT == 1) { voltage +=128;} } v=v+voltage; } voltage=v/100; return voltage; } //---------------------------------------------- UBYTE get_rc_code(void) { UBYTE rc_code, count; CLEAR_DISPLAY P2_7=1; // wait for long idle while(IRR==0); tone(A4,250); A: // wait for header while(IRR==1); // time header P2_7=0; TR0=0; TH0=0; TL0=0; // clear timer TMOD &= 0xf0; TMOD |= 0x01; // set up timer TR0=1; // start timer while (IRR == 0); // wait for end of pulse TR0=0; // stop the timer P2_7=1; ticks = TH0; ticks = (ticks << 8) + TL0; if(ticks<1500 OR ticks>3000){goto A;} // READ 7 BITS for ( count=1 ; count<=7 ; count++ ){ // wait for space to end TR0=0; TH0=0; TL0=0; // clear timer TMOD &= 0xf0; TMOD |= 0x01; // set up timer TR0=1; // start timer while (IRR == 1); // wait for end of space TR0=0; // stop the timer ticks = TH0; ticks = (ticks << 8) + TL0; if(ticks<300){goto A;} if(ticks>700){goto A;} // analyze pulse TR0=0; TH0=0; TL0=0; // clear timer TMOD &= 0xf0; TMOD |= 0x01; // set up timer TR0=1; // start timer while (IRR == 0); // wait for end of pulse TR0=0; // stop the timer ticks = TH0; ticks = (ticks << 8) + TL0; if(ticks<400){goto A;} if(ticks>1700){goto A;} rc_code=rc_code*2; // shift left if(ticks>1000){ rc_code=rc_code+1;} // } tone(C2,100); return(rc_code); } //--------------------------------- #define wait(x) TR0=0;TF0=0;TH0=255;TL0=(x);TR0=1;while(!TF0); #define I2C_WAIT TR0=0;TF0=0;TH0=255;TL0=250;TR0=1;while(!TF0); #define SCLK P2_0 #define SDATA P2_1 #define HIGH 1 #define LOW 0 UBYTE read_compass_register(UBYTE reg); UBYTE i2c_read(void); void i2c_write(UBYTE input_data); void i2c_start(void); void i2c_stop(void); //------------------------------------------------------------------------------ // I2C Functions - Bit Banged //------------------------------------------------------------------------------ //------------------------------------------------------------------------------ // Routine: i2c_start // Inputs: none // Outputs: none // Purpose: Sends I2C Start Trasfer - State "B" //------------------------------------------------------------------------------ void i2c_start (void) { SDATA = HIGH; // Set data line high SCLK = HIGH; // Set clock line high I2C_WAIT SDATA = LOW; // Set data line low (START SIGNAL) SCLK = LOW; // Set clock line low I2C_WAIT } //------------------------------------------------------------------------------ // Routine: i2c_stop // Inputs: none // Outputs: none // Purpose: Sends I2C Stop Trasfer - State "C" //------------------------------------------------------------------------------ void i2c_stop (void) { unsigned char input_var; SCLK = LOW; // Set clock line low SDATA = LOW; // Set data line low I2C_WAIT SCLK = HIGH; // Set clock line high SDATA = HIGH; // Set data line high (STOP SIGNAL) I2C_WAIT input_var = SDATA; // Put port pin into HiZ } //------------------------------------------------------------------------------ // Routine: i2c_write // Inputs: output byte // Outputs: none // Purpose: Writes data over the I2C bus //------------------------------------------------------------------------------ void i2c_write (unsigned char output_data) { unsigned char index; for(index = 0; index < 8; index++) // Send 8 bits to the I2C Bus { // Output the data bit to the I2C Bus SDATA = ((output_data & 0x80) ? 1 : 0); output_data <<= 1; // Shift the byte by one bit SCLK = HIGH; // Clock the data into the I2C Bus I2C_WAIT SCLK = LOW; I2C_WAIT } index = SDATA; // Put data pin into read mode SCLK = HIGH; // Clock the ACK from the I2C Bus I2C_WAIT SCLK = LOW; I2C_WAIT } //------------------------------------------------------------------------------ // Routine: i2c_read // Inputs: none // Outputs: input byte // Purpose: Reads data from the I2C bus //------------------------------------------------------------------------------ unsigned char i2c_read (void) { unsigned char index, input_data; index = SDATA; // Put data pin into read mode input_data = 0x00; for(index = 0; index < 8; index++) // Send 8 bits to the I2C Bus { input_data <<= 1; // Shift the byte by one bit SCLK = HIGH; // Clock the data into the I2C Bus I2C_WAIT input_data |= SDATA; // Input the data from the I2C Bus SCLK = LOW; I2C_WAIT } return input_data; } //==========================================\ UBYTE read_compass_register(UBYTE reg){ UBYTE val; i2c_start(); i2c_write(0xC0); i2c_write(reg); i2c_start(); i2c_write(0xC1); TR0=0;TF0=0;TH0=255;TL0=-50;TR0=1;while(!TF0); // 15 is ok, 10 isn't, 50 is suggested val = i2c_read(); i2c_stop(); return val; } //================ #include "alt.c"