for bluetooth
Dependencies: btbee m3pi_ng mbed
Fork of WarehouseBot1 by
Diff: Robot-bae8eb81a9d7/main.cpp
- Revision:
- 2:2d147091491d
- Parent:
- 1:2db3ccba18c8
- Child:
- 3:4284d7cdb68e
--- a/Robot-bae8eb81a9d7/main.cpp Wed Jun 03 14:29:48 2015 +0000 +++ b/Robot-bae8eb81a9d7/main.cpp Thu Jun 04 11:57:24 2015 +0000 @@ -6,7 +6,7 @@ m3pi robot; Timer timer; Timer time_wait; -#define MAX 0.75 +#define MAX 0.5 #define MIN 0 #define P_TERM 2.5 @@ -55,7 +55,7 @@ time_wait.start(); - turns = blah[(3-1)*6+(2-1)]; + turns = blah[(4-1)*6+(2-1)]; while(Run) { time_wait.reset(); //Get raw sensor values @@ -76,10 +76,22 @@ if(turns.at(direction) == 'L'){ + while(x[0] > 300){ + goStraight(); + robot.calibrated_sensor(x); + } previous_pos = 0; robot.stop(); //wait(1); - turnLeft(); + while(/*x[0] > 300 &&*/ x[2] > 300){ + turnLeft(); + robot.calibrated_sensor(x); + } + + while((x[0] > 300) || (x[2] < 300)){ + turnLeft(); + robot.calibrated_sensor(x); + } robot.stop(); //continue; /*wait(1); @@ -90,7 +102,15 @@ previous_pos = 0; robot.stop(); //wait(1); - turnRight(); + while(x[4] > 300 && x[2] > 300){ + turnRight(); + robot.calibrated_sensor(x); + } + + while((x[4] > 300) || (x[2] < 300)){ + turnRight(); + robot.calibrated_sensor(x); + } robot.stop(); /*wait(1); @@ -99,8 +119,11 @@ } else{ robot.stop(); - wait(1); - goStraight(); + //wait(1); + while(x[0] > 300 || x[4] > 300){ + goStraight(); + robot.calibrated_sensor(x); + } //wait(1); } robot.cls(); @@ -177,28 +200,28 @@ void turnRight(){ - Timer turner; - turner.start(); - while (turner.read_ms() < 130){ + //Timer turner; + //turner.start(); + //while (turner.read_ms() < 10){ robot.right(.5); - } - turner.stop(); + //} + //turner.stop(); } void turnLeft(){ - Timer turner; - turner.start(); - while (turner.read_ms() < 130){ +// Timer turner; + // turner.start(); + // while (turner.read_ms() < 10){ robot.left(.5); - } - turner.stop(); + // } + //turner.stop(); } void goStraight(){ - Timer turner; - turner.start(); - while (turner.read_ms() < 25){ + // Timer turner; + // turner.start(); + // while (turner.read_ms() < 5){ robot.forward(.5); - } - turner.stop(); + // } + // turner.stop(); } \ No newline at end of file