Tuesday, March 11, 2025

QTR-8A PID Line Follower and L293D

 #include <AFMotor.h> // Motor Shield Library

#include <QTRSensors.h> // QTR Sensor Library


// set to 1kHz PWM frequency

AF_DCMotor motor1(1, MOTOR12_1KHZ); //create motor #1 using M1 output on Motor Drive Shield

AF_DCMotor motor2(2, MOTOR12_1KHZ); //create motor #2 using M2 output on Motor Drive Shield


// note that KP < KD

#define KP 0.02

#define KD 2

#define M1_minimum_speed 150

#define M2_minimum_speed 150

#define M1_maximum_speed 250

#define M2_maximum_speed 250

// speed can be between  0 and 255 - 0 is LOW and 255 is HIGH.


QTRSensors qtr;


const uint8_t sensorCount = 6;

uint16_t sensorValues[sensorCount];


void setup() {

  qtr.setTypeAnalog();

  qtr.setSensorPins((const uint8_t[]){A0, A1, A2, A3, A4, A5}, sensorCount);

  qtr.setEmitterPin(2);


  pinMode(LED_BUILTIN, OUTPUT);

  digitalWrite(LED_BUILTIN, HIGH);

  set_motors(0,0);


  int i;


  for (int i = 0; i < 100; i++) {

    if (i < 25 || i >= 75) {

      turn_right();

    }

    else {

      turn_left();

    }

    qtr.calibrate();

    delay(20);

  }


  stop();

  digitalWrite(LED_BUILTIN, LOW); // end calibration

  delay(1000);

}


int lastError = 0;


void loop() {

  // read calibrated sensor values and obtain a measure of the line position

  // from 0 to 7000

  uint16_t position = qtr.readLineBlack(sensorValues);


  // for PID

  int error = position - 3500;

  int motorSpeed = KP * error + KD * (error - lastError);

  lastError = error;


  int leftMotorSpeed = M1_minimum_speed + motorSpeed;

  int rightMotorSpeed = M2_minimum_speed - motorSpeed;

  

  // set motor speeds using the two motor speed variables above

  set_motors(leftMotorSpeed, rightMotorSpeed);

}


void set_motors(int motor1speed, int motor2speed) {

  if (motor1speed > M1_maximum_speed) motor1speed = M1_maximum_speed;

  if (motor2speed > M2_maximum_speed) motor2speed = M2_maximum_speed;

  if (motor1speed < 0) motor1speed = 0; 

  if (motor2speed < 0) motor2speed = 0; 


  motor1.run(FORWARD); 

  motor2.run(FORWARD);

  motor1.setSpeed(motor1speed); 

  motor2.setSpeed(motor2speed);

}


void stop() {

  motor1.run(RELEASE);

  motor2.run(RELEASE);

}


void turn_left() {

  motor1.run(BACKWARD);

  motor2.run(FORWARD);

}


void turn_right() {

  motor1.run(FORWARD);

  motor2.run(BACKWARD);

}

No comments:

Post a Comment