Posts Tagged Line follower

Microbo(t) – Advanced line follower

Although it is one of the classics of robotics for beginners, the line follower robot, made ​​at high level, is quite complex. On Youtube you can see line follower running at 3 m / s and more, with optimization and maximum performance research that achieves discrete levels.

Usually a line follower competition is based on pure speed and the path is quite linear and simple, with large curves and wide straights. In this case the hardware part is the most important, because the sw part is quite simple to build. it is important to find the right compromise between the mechanical parts and the engine, to make it running as fast as possible. Unfortunately requires a lot of money, because the engine performance search or the wheels with special tires can be very expensive.The alternative is based on paths that are rather difficult or very twisted, with right angles, intersecting lines, lines breaks, obstacles and so on. In this case the HW is much less important. More important is the algorithm and then the sw. The ability of the robot builder is to build a powerful algorithm that allows the robot to drive fast in every situation.

In this tutorial I would describe the robot that I have realized, that is able to face a tortuous path made ​​of curves at 180 ° rather than tight coils, trying to  have a good speed.
The robot ,according to tradition, was home built. It is also already equipped with an infrared sensor front in case you wish to use it in a path with obstacles.

Questo è Microbo(t) – line follower robot:

It ‘s built with the following elements:
– Chassis 5 mm PVC foam (few cents)
– Arduino Nano (about 40 euros)
– Drive Pololu 50:1 HP (about 30 euros both)
– Pololu motor bracket (both about 6 euros)
– Caster wheel  Pololu 3.8 “plastic (about 3 euros)
– Pololu Wheels 42×19 (both about 10 euros)
– Motor driver SparkFun TB6612FNG (about 9 euros)
– Sharp IR Distance sensor 4-30 cm (about 15 euros)
– Sensor line Pololu QT-8RC (about 12 euros)
– 7.4V 900mAh Battery Li-Po (about 9 euros)
– some screws and wires
As you can see the components expensive are Arduino Nano and the motors. Nothing forbids to use a traditional Arduino with an obvious saving of money. In my configuration it weighs about 160 grams. You can do much better, in fact on the internet there are line follower with Arduino that weigh 100 grams.

 

 

Some comments on hw components used. The driving system, formed by Pololu wheels and  motors is almost good. I think that even better is using HP 100:1 Pololu motors which provide even more traction and fluidity in the changes of direction, even if it has a lower number of revolutions/minute. I tested also the 30:1 motors, but they were too nervous. Absolutely bad is the plastic wheel caster form Pololu. Unfortunately I had no other small than this, so I kept it. Not recommend its use. Terrible.

The motor driver SparkFun TB6612FNG is a little undersized. In fact it provides 1.2A at full speed, when the Pololu HP motors  may require up to 1.6A. But I had no problem with these drivers and they still work, so I can only advise them. Unfortunately they have a lot of wires, 7 for driving, 2 for the Vcc voltage (+5 V), one (or two with the ground) for the motor voltage and 4 wires for motors. In total 14 wires that are several. They are simple to program and manage. The full brake function is not good. In fact, if you need to brake, however, takes a little bit to stop, victim of inertia. I think that the engines 100:1 can help on this.

The line sensor Pololu QT-8RC is good. It provides out-of-the-box a digital output and can be connected directly to the Arduino digital ports. After a stage of self-learning during the first few seconds (see the video), it is able to calibrate with the best values ​​taking into account the reflectivity of the surface and the ambient light conditions. It can follow the black lines on white background or white on black background. For this sensor there is an Arduino  library written by Pololu that provides a value between 0 and 8000 depending on the sensor (from left to right) which is above the black line. I modified the library to get a response that goes from -800 to +800 with zero when the line is well below the IR sensor in the middle. This from my point of view makes easier the control. The only real problem I had was in the presence of right angles. In this case the robot has not always stopped in time and managed to turn. Unfortunately I have no videos on this particular problem.

Once built the robot, the biggest difficulty is the control parameters determination, that allow the robot to come back to the line when goes away. In this case I have put in place the usual PID control, although in my version was reduced only in PD, proportional and derivative. The integral control, with the frequent changes of direction, is extremely difficult to detect.
I also wrote  some simple routines for the detection of right angles. In this case the robot tries to stop and turns 90°. This technique has worked quite, but you can sure do better.

For the  IR front sensor I didn’t have any important test for obstacle avoidance. The main problem is due to the need to rotate the robot for the obstacle avoidance operating in open-chain, ie, without feedback.  The robot should pass the obstacle, but that succeeded a few times because the motors battery voltage varies over time, with a variation of path. I did not do further tests, but there are two possibilities:

  • a dc-dc converter boost 4-25v ​​for example like in the Pololu 3pi robot that maintains a constant input voltage to the motors and that have a good precision even in the absence of encoder
  • the encoders in the wheels with angles measurement

The dc-dc converter costs less than 10 euros, while the cost for the Pololu encoder  is about 25 euros. Maybe in the next version of the Microbo(t) I will decide which solution to adopt. Clearly the solution encoder is more sophisticated but requires more programming effort (and verify that there are still pins available on the Arduino!).

This is the code for Arduino, commented but not very clean. Link

This is the Microbo(t) in action:

 

Tags: , ,

Linea – Line follower

 

Linea is my first line follower based on Arduino.

A line follower is a robot for beginners. In fact it is very simple to build a line follower and only few components are required :

– a robot chassis

– IR sensors for line tracking (black or white line)

– two motors (servos or gear motors)

– an Arduino to drive the motors and to implement control logic

– Batteries, jumpers, screws and other hardware

If you use  gear motors it is important to use also a motors driver, because Arduino can’t feed the motors with the high current required.

 

IR SENSORS

The sensors used in line follower robot are Infrared sensors and they are made with 2 different components:

– a light emitter

– a light receiver

When the emitter emits light, the light is reflected by the floor. If the line is white and the sensor is above the line, the white line reflect all the light, so it permits to understand that the sensor is effectively above the line. Instead if the sensor is over the black surface, the sensor doesn’t reflect the light, so we can understand that the sensor isn’t above the line.
If we have many IR sensors, knowing which sensor is above the line, lets to understand if the robot is going out from the middle of the line,  at the right or the left side. In the picture above are shown 5 sensors, but is not unusual to use 8 or 10 sensors. The minimum required is 3 sensor (left, straight, right).

 

The CONTROL

The robot, mostly if the line is curved, will go out of the path. It is important to teach to the robot how to maintain above the line. Usually, it is possible to do this with a motion control and the PID (Proportional-derivative-integral) control is the most famous. This control will try to compensate the error, i.e. the misalignment from the line. You can find some details about PID in wikipedia.

This picture shows the criteria used for the control:

 

The combined readings from the sensors are used to understand if the correction done by the control have to be hard or soft.

 

Linea – The line follower robot

This robot was shown on the Arduino Day, in Rome (Italy), in April 2011 and  use a Pololu sensor with 8 IR leds ( link), very cheap (14 euros). It is offered with an Arduino library, made by Pololu. This library resolves all the interfacing problems with Arduino (yeah!).

 

 

The robot chassis is build using a cheap DFRobot module (link) that for less than 30 euros, offers also 2 gear motors, 2 motor supports and 2 wheels:

The motor driver is a Sparkfun module (link) , very very cheap (8 euros), that can feed up to 1.2A. It supports 2 gear motors and lets the PWM usage.

For my convenience I assembled the motor drivers on a breadboard shield, but it is enough a normal breadboard. Others components (ball caster, sensor support, batteries) are self made or bought in a hardware shop.

This is Linea:

 

 

 

Here Linea in action:

 

This is the code used:

#include <PololuQTRSensors.h>
// motor driver pin
#define out_STBY 6
#define out_B_PWM 9
#define out_A_PWM 3
#define out_A_IN2 4
#define out_A_IN1 5
#define out_B_IN1 7
#define out_B_IN2 8
#define motor_A 0
#define motor_B 1
#define motor_AB 2

#define NUM_SENSORS 8 // number of sensors used - numero di sensori usati
#define TIMEOUT 2500 // waits for 2500 us for sensor outputs to go low - aspetta 2500 us prima di mandare low i sensori
  //define QTR pololu sensor
PololuQTRSensorsRC qtrrc((unsigned char[]) {2, 12, 11, 10, 17, 16, 15, 14}
 , NUM_SENSORS, TIMEOUT, 255);
unsigned int sensors[NUM_SENSORS];
  void setup()
{
  Serial.begin(115200);
  // define motor drive output pin - definisci i pin di output del motore
  pinMode(out_STBY,OUTPUT);
  pinMode(out_A_PWM,OUTPUT);
  pinMode(out_A_IN1,OUTPUT);
  pinMode(out_A_IN2,OUTPUT);
  pinMode(out_B_PWM,OUTPUT);
  pinMode(out_B_IN1,OUTPUT);
  pinMode(out_B_IN2,OUTPUT);
  motor_standby(false);// motor stand-by off and stop - togli i motori dallo stand-by e fermali
  stopMotors();
  delay(2000);
  SensorCalibration(); // sensor calibration - calibra i sensori
  delay(2000);
}

void loop()
{
  follow_segment(); // follow the black line - segui la linea nera
}
// PID parameters
int Kp=120;
int Ki=100;
int Kd=100;
// follow the black line - segui la linea nera 
void follow_segment()
{
  int last_proportional = 0;
  long integral=0;
  int primo=0;
  int posizione = qtrrc.readLine(sensors); // read the IR sensors - leggi i sensori IR 
  long int proportional = posizione;
  int P = proportional * Kp/1000; // Proportional parameter 
  long int derivative = proportional - last_proportional; //Derivative parameter
  if (primo==0) // firt cycle set derivative to zero - al primo giro imposta il derivativo a zero
     {
      primo=1;
      derivative=0;
    }
  int D=derivative*Kd/1000;
  integral += proportional;
  int I=integral*Ki/1000; //integral parameter 
  // Remember the last position - ricorda l'ultima posizione
  last_proportional = proportional;
  int PID =P + I + D; //calculate the PID 
  // print some values on the serial port - scrivi qualche valore sulla seriale
  unsigned char zz;
   for (zz = 0; zz < NUM_SENSORS; zz++)
    {
      Serial.print(sensors[zz]);
      Serial.print(' ');
    }
    Serial.print(" position: ");
    Serial.print(posizione);
    Serial.print(" P:");
    Serial.print(P);
    Serial.print(" I:");
    Serial.print(I);
    Serial.print(" D:");
    Serial.print(D);
    Serial.print(" PID:");
    Serial.print(PID);
  // set the values for the motors based on the PID gain - setta i valori del motore basati sul PID
    const int maximum = 40; // the maximum speed
     if (PID > 0){
       if (PID > maximum) PID=maximum;
       motor_speed2(motor_B,maximum);
       motor_speed2(motor_A,maximum-PID);
      Serial.print(" Motore_B:");     Serial.print(maximum);
    Serial.print(" Motore_A:");      Serial.print(maximum-PID);
      }
      else {
       if (PID < -maximum) PID=-maximum;
       motor_speed2(motor_B,maximum+PID);
        motor_speed2(motor_A,maximum);
      Serial.print(" Motore_B:");     Serial.print(maximum+PID);
    Serial.print(" Motore_A:");      Serial.print(maximum);
      }
      Serial.println("");
}
// ------------------ stop the robot - ferma il robottino ----------------------- 
void stopMotors(){
  motor_brake(motor_A);
  motor_brake(motor_B);
}
// ------------------ Motor driver mgmt routines - routine per gestire i motori ----------------------- 
void motor_speed2(boolean motor, char speed) { //speed from 0 to 100
  if (motor == motor_A)
   speed = -speed;
  byte PWMvalue=0;
  PWMvalue = map(abs(speed),0,100,50,255); //anything below 50 is very weak
  if (speed > 0)
    motor_speed(motor,0,PWMvalue);
  else if (speed < 0)
    motor_speed(motor,1,PWMvalue);
  else {
    motor_coast(motor);
  }
}
void motor_speed(boolean motor, boolean direction, byte speed) { //speed from 0 to 255
  if (motor == motor_A) {
    if (direction == 0) {
      digitalWrite(out_A_IN1,HIGH);
      digitalWrite(out_A_IN2,LOW);
    } else {
      digitalWrite(out_A_IN1,LOW);
      digitalWrite(out_A_IN2,HIGH);
    }
    analogWrite(out_A_PWM,speed);
  } else {
    if (direction == 0) {
      digitalWrite(out_B_IN1,HIGH);
      digitalWrite(out_B_IN2,LOW);
    } else {
       digitalWrite(out_B_IN1,LOW);
      digitalWrite(out_B_IN2,HIGH);
    }
    analogWrite(out_B_PWM,speed);
  }
}
// stand-by motor
void motor_standby(boolean state) { //low power mode
  if (state == true)
    digitalWrite(out_STBY,LOW);
  else
    digitalWrite(out_STBY,HIGH);
}
// stop the motors
void motor_brake(boolean motor) {
  if (motor == motor_A) {
    digitalWrite(out_A_IN1,HIGH);
    digitalWrite(out_A_IN2,HIGH);
  } else {
    digitalWrite(out_B_IN1,HIGH);
    digitalWrite(out_B_IN2,HIGH);
  }
}
// motors coast - fai girare i motori in folle
void motor_coast(boolean motor) {
  if (motor == motor_A) {
    digitalWrite(out_A_IN1,LOW);
    digitalWrite(out_A_IN2,LOW);
    digitalWrite(out_A_PWM,HIGH);
  } else {
    digitalWrite(out_B_IN1,LOW);
     digitalWrite(out_B_IN2,LOW);
    digitalWrite(out_B_PWM,HIGH);
  }
}
// IR sensor calibration 
void SensorCalibration() {
  int counter, i;
  for (counter=0; counter<40; counter++)
  {
    if (counter < 10 || counter >= 30) {
      motor_speed2(motor_A,10);
      motor_speed2(motor_B,-10);
    }
    else   {
      motor_speed2(motor_A,-10);
      motor_speed2(motor_B,10);
    }
    qtrrc.calibrate();
    // Since our counter runs to 80, the total delay will be
    // 80*20 = 1600 ms.
    delay(20);
  }
     // print the calibration minimum values measured when emitters were on
    for (i = 0; i < NUM_SENSORS; i++)
  {
    Serial.print(qtrrc.calibratedMinimumOn[i]);
    Serial.print(' ');
  }
  Serial.println();
    // print the calibration maximum values measured when emitters were on
  for (i = 0; i < NUM_SENSORS; i++)
  {
    Serial.print(qtrrc.calibratedMaximumOn[i]);
    Serial.print(' ');
  }
  Serial.println();
  Serial.println();
  stopMotors();
  delay(2000);
}

Tags: , ,