A repo for the code of the Line Following robot we are making for Robotex 2022
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

122 lines
2.7KB

  1. //Make sure to install the library
  2. #include <QTRSensors.h>
  3. QTRSensors qtr;
  4. const uint8_t SensorCount = 8;
  5. uint16_t sensorValues[SensorCount];
  6. float Kp = 0.07; //set up the constants value
  7. float Ki = 0.0008;
  8. float Kd = 0.6;
  9. int P;
  10. int I;
  11. int D;
  12. int lastError = 0;
  13. boolean onoff = false;
  14. //Increasing the maxspeed can damage the motors - at a value of 255 the 6V motors will receive 7,4 V
  15. const uint8_t maxspeeda = 150;
  16. const uint8_t maxspeedb = 150;
  17. const uint8_t basespeeda = 100;
  18. const uint8_t basespeedb = 100;
  19. //Set up the drive motor carrier pins
  20. int mode = 8;
  21. int aphase = 9;
  22. int aenbl = 6;
  23. int bphase = 5;
  24. int benbl = 3;
  25. //Set up the buttons pins
  26. int buttoncalibrate = 17; //pin A3
  27. int buttonstart = 2;
  28. void setup() {
  29. Serial.begin(9600);
  30. qtr.setTypeRC();
  31. //Set up the sensor array pins
  32. qtr.setSensorPins((const uint8_t[]){10, 11, 12, 14, 15, 16, 18, 19}, SensorCount);
  33. qtr.setEmitterPin(7);//LEDON PIN
  34. pinMode(mode, OUTPUT);
  35. pinMode(aphase, OUTPUT);
  36. pinMode(aenbl, OUTPUT);
  37. pinMode(bphase, OUTPUT);
  38. pinMode(benbl, OUTPUT);
  39. digitalWrite(mode, HIGH);
  40. delay(500);
  41. pinMode(LED_BUILTIN, OUTPUT);
  42. boolean Ok = false;
  43. while (Ok == false) { //the loop won't start until the robot is calibrated
  44. if(digitalRead(buttoncalibrate) == HIGH) {
  45. calibration(); //calibrate the robot for 10 seconds
  46. Ok = true;
  47. }
  48. }
  49. forward_brake(0, 0);
  50. }
  51. void calibration() {
  52. digitalWrite(LED_BUILTIN, HIGH);
  53. for (uint16_t i = 0; i < 400; i++)
  54. {
  55. qtr.calibrate();
  56. }
  57. digitalWrite(LED_BUILTIN, LOW);
  58. }
  59. void loop() {
  60. if(digitalRead(buttonstart) == HIGH) {
  61. onoff =! onoff;
  62. if(onoff = true) {
  63. delay(1000);//a delay when the robot starts
  64. }
  65. else {
  66. delay(50);
  67. }
  68. }
  69. if (onoff == true) {
  70. PID_control();
  71. }
  72. else {
  73. forward_brake(0,0);
  74. }
  75. }
  76. void forward_brake(int posa, int posb) {
  77. //set the appropriate values for aphase and bphase so that the robot goes straight
  78. digitalWrite(aphase, LOW);
  79. digitalWrite(bphase, HIGH);
  80. analogWrite(aenbl, posa);
  81. analogWrite(benbl, posb);
  82. }
  83. void PID_control() {
  84. uint16_t position = qtr.readLineBlack(sensorValues);
  85. int error = 3500 - position;
  86. P = error;
  87. I = I + error;
  88. D = error - lastError;
  89. lastError = error;
  90. int motorspeed = P*Kp + I*Ki + D*Kd;
  91. int motorspeeda = basespeeda + motorspeed;
  92. int motorspeedb = basespeedb - motorspeed;
  93. if (motorspeeda > maxspeeda) {
  94. motorspeeda = maxspeeda;
  95. }
  96. if (motorspeedb > maxspeedb) {
  97. motorspeedb = maxspeedb;
  98. }
  99. if (motorspeeda < 0) {
  100. motorspeeda = 0;
  101. }
  102. if (motorspeedb < 0) {
  103. motorspeedb = 0;
  104. }
  105. //Serial.print(motorspeeda);Serial.print(" ");Serial.println(motorspeedb);
  106. forward_brake(motorspeeda, motorspeedb);
  107. }