PID algorithm implementation (PID Controlled Line Following Robot)

pid

PID algorithm is a process of proportional integral derivative for control system implementation. This is the project guide about PID algorithm and how to make PID robot using pic microcontroller. We will discuss PID algorithm implementation and PID formula. Making a robot using pic16f877a microcontroller and PID algorithm is the best example for PID control system.


00: Contents:


  1. Introduction to PIC Microcontroller (PIC 18f4550)
  2. Introduction to PID algorithm
  3. Sensor selection
  4. PID Controller Algorithms
  5. Code & Tuning
  6. SCHEMATIC and simulations
  7. Code

The basic purpose of this project is to develop the understanding of PID algorithm. Some of the basic things about making robot will not be covered here. For this, you have to see the robotics section about making a robot and other related stuff like motor selection motor driver etc. The core objective is to discuss the implementation of PID control system.


00: COMPONENTS:


Components that we have used in building a PID base Line following Robots:

  • ·       PIC micro controller 18f4550
  • ·       IR sensor
  • ·       Chesses and Motor
  • ·       LM 324
  • ·       PID algorithm

01: Introduction to PIC Microcontroller (PIC 18f4550)


There were two main alternatives regarding the choice of microcontroller: PIC18F family (specifically the PIC18F4550, due to familiarity, and it having the needed features and number of ports), or Arduino (most likely the Nano or UNO, since both have enough processing power and I/O pins for it to be unnecessary to consider the more powerful models).

PIC 18f4550:

The PIC18F4550 is the highest performance USB-equipped model in Microchip, INC. popular PIC18 8-bit microcontroller line. It features (Microchip, Inc. 2009b, Microchip Inc. 2009a):

  •  32 KB Flash Program Memories.
  •  A 12 MIPS CPU
  •  2KB RAM.
  • 256-byte data EEPROM
  • 1 x A/E/USART Port
  • 1 x MSSP (SPI/I2C) Port
  • 1 x CCP & 1 x ECCP
  •  1 x 8-bit & 3 x 32-bit Timers
  • 13 x 10-bit Analog Inputs
  •  2 x Comparators.
  • 1 x USB 2.0.
  • 35 x Digital I/O Pins

This microcontroller has been used extensively. It can be programmed natively in Microchip PIC assembly, or in C18, Microchip’s implementation of the C programming language for use with their PIC18 line.

Due to their popularity, there exist a great number of open-source projects developed for the PIC18F line, along with libraries, tutorials, and many articles on coding and developing using these microcontrollers. They are also used to great extent professionally.


02: Sensor selection


IR sensor:

Depending on the accuracy we have to choose IR sensor. The basic concept of IR(infrared) is obstacle detection by transmitting an IR signal(radiation) in a direction and a signal is received at the IR receiver when the IR radiation bounces back from a surface of the object.

For Ir object can be anything the IR LED transmits the IR signal on to the object and the signal is reflected back from the surface of the object. The reflected signals are received by an IR receiver.

IR Transmitter:
IR transmitter is modulation of the information signal with the carrier signal because the receiver modules which are available off-the-shelf are made for a particular carrier frequency. So it is clear that when you chose a particular IR receiver module, you also need to transmit the modulated wave with the same carrier frequency of that of an IR receiver module. Modulating a 38 kHz carrier signal.

IR Receiver:
An IR receiver with readily available off-the-shelf modules. The receiver is designed for 38 kHz carrier signal; hence the IC selected should work for the same frequency. The IC TSOP4838 will serve as a receiver module, which is compatible with both TTL and CMOS logic. This means that we can directly get a digital signal from the receiver module and then connect it to the microcontroller. The Implementation of IR receiver is explained using an LED as an indicator.


03: Introduction to PID algorithm:


The Proportional Integral and Derivative (PID) controller is the control algorithm and mostly used in industrial control.  PID  algorithm allows engineers to operate them in a simple and straightforward way. The name shows PID, The three words  Proportional, Integral, and Derivative.

The Proportional Response:

The proportional component in PID algorithm is the difference between the set point of the system and the process variable. Now, this difference is called Error. The proportional gain (Kp) is the ratio between output response and the error signal.

The Integral Response

Integral in PID is the sum of the error term over the time. If the result is a small error the integral component will increase slowly. Now the integral term will continually increase over the time unless and until the error is going to be zero, so the ultimate effect is driving the Steady-State error towards zero. The difference between the process variable and the set point is the Steady state error.

The Derivative Response:

The function of the derivative component is to decrease the output of the process variable is going to increase. The derivative is the rate of change of the process variable. The Increase in the derivative time (Td)  will make the system to react strongly and to make changes in the error term. This will increase the overall speed. The very small (Td) the derivative time is used in most practical systems.

Derivative Response is sensitive and highly sensitive to the noise and in the process variable. If the feedback is noisy or the control loop rate is very much slower, The control system will be unstable due to derivative response.


04: PID Controller Algorithms:


1 In a case when robot is deviated to left it then pushes to move towards right

  1. In a case of deviation towards right, it is forced to move towards left

The accomplishment of this task gives our robot is following the zigzag path Using this method the speed we were giving was much less as error getting by using PID. And this technique was also not reliable for the turns. To apply this algorithm it was better to use the error calculation method after calculating error giving motor it’s proportional value and then it changes speed and in turn, it gets back to the line.

e.g.-the deviation ranges between -3 to +3.

Kp is the proportionality constant it will give negative value when the robot is towards left of the line then the right motors gets slow down.

This is a good practical approach for many cases. But not suitable because of these reasons

  1. It affects the accuracy of the robot when the robot is not much effective it gets back to mean position very slowly.
  2. To solve this problem we have to increase its proportionality contact but it will then overshoot when the robot comes to mean position due to inertia-cross to another side then again overshoot results in deviating result.

05: PID Controller Algorithms:


PID is a feedback mechanism.

It has three components on which it works that are

1: error

2: time of deviation

3: overshoots

Efficiency of the PID algorithm is based on these three parameters these helps to reach at mean position much faster

The three constants are set by hit and trial method experimentally.

    1. Kp
    2. Ki
    3. Kd

Using only kp parameter the robot will be applied and give the results as the classical line following algorithm discussed earlier.

Ki: because of ki robot is forced to follow mean position.
Kd: kd does not allow the robot to perform any deviation


06: PID Code:


Given below is the code for measuring the deviation

‘00000001’ this means robot is towards rightmost this code works in a manner that is robot is at right the deviation will be recorded negative

Getting these results PID then sums all the previous deviations and generates an integral called total error. The difference of the deviation is measured by the derivative. The error calculated is then sent to this code it will give the correction

These lines should run in each iteration.


07: PID Tuning:


PID tuning is greatly affected by the floor where it is going to be use and the track where the robot is going be run and these physical parameters cannot be calculated mathematically. For example motor inductance, friction center of mass etc. these quantities can be just guessed and applied by hit and trial method.

 Sensor circuit:

Sensors are the array of 7 IR sensors which are connected with operational amplifier LM324 which converting the analog output of the sensor into digital by comparing the threshold level of line then the digital output of op amp is given to microcontroller.

Main circuit:

The sensor array that we have made in the last lab will be connected to PORT B. the motor driver IRFZ44N is a Mosfet. We have us Mosfet due to the fact that it can drive high voltage and currently is per requirement we need to have a motor driver that has the capability to handle high voltage and current.

For the accuracy of the robot and requirement of the algorithm, we selected IRFZ44N. To control the motion of the motors and to control the speed of the motors a PWM waveform with variable duty cycle is applied to the gate of the IC.

The main circuit of the robot is on 18f4550 which is most popular micro controller of pic micro’s having 12 bit ADC resolution 8 analog to digital pins which are used for tuning PID occupied by potentiometers 2 CCP modules which controls PWM given to motors which ultimately controls the speed of robot having 33 I/O pins in which 8 is used for reading data from sensors and 8 are used in 16×2 LCD display interface circuit.

Microcontroller take decision on the base is of sensor outputs and after applying PID it controls the motion of robot by changing the speed of motors accordingly.


08: Motor driver:


Our motors are derived by IRFZ44N.IRFZ44N is a motor driver made up of MOSFETs. Only code is not sufficient for desired results.By continuously hit and trials it will effect more. It is not necessary to use all three parameters P, I and D.If only PI is enough it is not necessary to use derivative part.PID also requires settling time that is why it will also consume this time in showing accurate results.


09: SCHEMATIC:


 


10: Output:


The robot is successfully following the given area.

The output is very much accurate and deviations are much reduced to a very low level.

Kp=50

Kd=4

In this project, our main focus was to cover the PID algorithm implementation. Some of the sections about making robot are not included here.

Below is the Code of PIC microcontroller. Enter E-mail address to get complete code file and practice it.


11: PID Code:


 

All rights reserved www.makeitmech.com
PID line following Robot Code:

#include <18f4550.h>
#device adc=10
#fuses NOWDT,PUT,HS,PROTECT
#use delay(clock=20M)
#use rs232(baud=9600,xmit=PIN_C6,rcv=PIN_C7)
#include <lcd.c>
\\Variable Initialization 
char c;
float value,pwm1,temp,pwm2,error,preverror,totalerror,kp,ki,kd,filter0;
intpb,speedleft,speedright,filter;
charch;

void main(void)
{
enable_interrupts(INT_RDA);		//Serial Interrupt Enable 
enable_interrupts(GLOBAL);		//Global Interrupt Enable
setup_ccp1(CCP_PWM);			// CCP1 Initialization 
setup_ccp2(CCP_PWM);			// CCP2 Initialization
totalerror=0;				// PID LOOP Variables
error=0;					
preverror=0;
filter0=0;
filter=0;
kp=0;
ki=0;
kd=0;
pwm1=0;
pwm2=0;
lcd_init();				//LCD Initialization 
delay_ms(10);
//lcd_gotoxy (1,1);			
//delay_ms(3000);			
output_high(PIN_D3);			//Status LED Indication
delay_ms(500);
output_low(PIN_D3);
delay_ms(500);
while(1)					//Main loop
{
if(!input(PIN_E0))
{
while(!input(PIN_E0))
{
setup_adc_ports( ALL_ANALOG );	//Initialization of ADC Port	
setup_adc(ADC_CLOCK_INTERNAL );	// ADC Clock Internal 
set_adc_channel(0);				
delay_us(5);				
filter0=read_adc();			//PID Filter Value Input
filter0=((filter0/818.4)*120);
filter=filter0;
set_adc_channel(1);				// Channel select for PWM  
delay_us(5);				
pwm1=read_adc();				
pwm1=((pwm1/818.4)*120);			// Input max PWM
lcd_gotoxy (1,1);
printf(lcd_putc,"  filter=%d\npwm1 power=%0.0f",filter,pwm1);
printf(lcd_putc,"");
delay_ms(200);
input_e();
}
}
else
{
while(1)							
{
setup_adc_ports( ALL_ANALOG );		//PID Loop 
setup_adc(ADC_CLOCK_INTERNAL );
set_adc_channel(0);				// Filter Value Input
delay_us(5);
filter0=read_adc();
filter0=((filter0/818.4)*120);
filter=filter0;
set_adc_channel(1);				//PWM Value Input
delay_us(5);
pwm1=read_adc();
pwm1=((pwm1/818.4)*120);
set_adc_channel(2);				// KP Input 
delay_us(5);					
kp=read_adc();
kp=kp/34;
set_adc_channel(3);				// KI Input 
delay_us(5);					
ki=read_adc();
ki=ki/34;
set_adc_channel(4);				// KD Input 
delay_us(5);
kd=read_adc();
kd=kd/34;
pb = input_b();					//Reading Port B 
							//Digital Data for sensors
//whiteline black arena		
/	// Error Definitions for black //arena
if(pb==1 || pb==7 || pb==15)error=-6;
if(pb==3)error=-5;
if(pb==2)error=-4;
if(pb==6)error=-3;
if(pb==4)error=-2;
if(pb==12)error=-1;
if(pb==8)error=0;
if(pb==24)error=1;
if(pb==16)error=2;
if(pb==48)error=3;
if(pb==32)error=4;
if(pb==96)error=5;
if(pb==64 || pb==112 || pb==120)error=6;
*/


//black line white arena  	
// Error Definitions for black //arena
if(pb==126 || pb==96 || pb==112 || pb==120)error=-6;
if(pb==124)error=-5;
if(pb==125)error=-4;
if(pb==121)error=-3;
if(pb==123)error=-2;
if(pb==115)error=-1;
if(pb==119)error=0;
if(pb==103)error=1;
if(pb==111)error=2;
if(pb==79)error=3;
if(pb==95)error=4;
if(pb==31)error=5;
if(pb==63 || pb==3 || pb==7 || pb==15)error=6;

pwm2=(kp*error)+(ki*totalerror)+(kd*(error-preverror));\\pid  Equat

totalerror+=pwm2;		// Adding prev_ error for Integral
preverror=error;		
speedleft=pwm1+pwm2;		// speed for left motor	
speedright=pwm1-pwm2;		// speed for right motor 
if(speedleft> filter  )	// Speed Filter for PID
{	
speedleft = filter;
}
else if(speedleft< 0)
{
speedleft = 0;
}
if(speedright> filter)
{
speedright= filter;
}
else if(speedright< 0)
{
speedright = 0;
}
set_pwm1_duty(speedleft);			// Output PWM to CCP1
setup_timer_2(T2_div_by_16,127,1);	
set_pwm2_duty(speedright);			// output PWM to CCP2
setup_timer_2(T2_div_by_16,127,1);
lcd_gotoxy (1,1); 	\\LCD Display Output
printf(lcd_putc,"P%0.0f,ML%dMR%d",pwm1,speedleft,speedright);
printf(lcd_putc,"");
lcd_gotoxy (1,2);
printf(lcd_putc,"C%d p%0.0f i%0.0f d%0.0f",pb,kp,ki,kd);
printf(lcd_putc,"");
//printf(" \n\r pwm1:%0.0f pwm2:%f kp:%f,ki:%f,kd:%f PORTB:%d error: %0.0f",pwm1,pwm2,kp,ki,kd,pb,error);
//delay_ms(200);
}
}
}
}

If you have any query then comment below and Subscribe to our YouTube channel for video Tutorials,

 

Exit mobile version