Making a Fast Mini Line Following Robot — FMLFR

1. INDRODUCTION

Robots are electromechanical programmable devices which has the ability to perform a specific task autonomously by replacing human actions. They are equipped with sensors, actuator and a control system which allows them to interact with the most suitable environment to perform the specific task effectively and precisely. Robots can be ranged from devices like industrial robotic arms to complex systems like humanoid robots.

Line following robots are mobile robots which follows a line very accurately on a predetermined path having a hardwired control circuit. The robot senses the line through infra-red signals and manoeuvres accordingly to stay on course while correcting any inclinations using a feedback mechanism thus forming a simple yet very effective closed loop system.

Basic operation of line following robots are capturing line position with sensors mounted at the front portion of the robot and steer the robot with a suitable steering mechanism to track the path. Operation of a line following robot can be divided into three sections.

1) Capturing the line position

This is usually implemented using photo reflective sensors ( IR sensors) and some use image sensors for image processing. This operation requires high resolution and high robustness given the fact that the complete sensing part plays a main role in providing the input reading to the processor.

2) Steering the robot to track the line.

This involves servo operation. Line following robots usually employ differential steering mechanisms for manoeuvring along the path. Differential steering is a fundamental mechanism used in many types of mobile robots, including line following robots, to achieve manoeuvrability and control over direction. Differential steering involves controlling the speeds of two independently driven wheels or tracks allowing the robot to turn by varying the speed difference between them. This is a versatile mechanism that enables precise control over the motion of the line following robot. This gives it the ease to navigate in complex paths, demonstrating agility and manoeuvrability in a variety of the environment.

3) Speed and position control mechanism.

Speed control is one of the important aspects to consider in the control mechanism of line following robots. In order to adapt to different lane conditions and track geometries, these robots require precise speed controlling. It is very crucial for maintaining stability when encountering curves, intersections or sharp turns along the path. Through speed modulation the robot can navigate these features while minimizing the risk of skidding or loosing track.

Feedback mechanisms are implemented in the speed control algorithms to monitor the speed and adjust in real time based on the deviations from the original path. PID control is used mostly to regulate the speed effectively in these type of robots.

In this project a line following robot is designed with an optimum mechanical structure to implement a mini fast line follower with a custom designed PCB and programmed using Atmega328P microcontroller.

Overall throughout different timelines mapping from the past the line followers have taken various of forms in terms of design and functionalities. Making the fast mini version of this line follower is what is being focused on, in this post.

2. PROJECT REQUIREMENTS

This project required the design and implementation of a mini, fast, line-following robot. Specifications of each project requirement is given below.

· Mini — Maximum dimensions of robot should be 10x10cm.

· Fast — Robot should move with a maximum speed of 300rpm.

· Line Follower — Robot should be able to follow a black line on a white surface.

The below are the paths expected to be completed by the robot.

Figure 1: Path 1
Figure 2: Path 2

3. RESEARCH ON THE OPTIMUM CHASSIS DESIGN.

As a result of our research we considered the below three designs for our robot’s chassis.

Figure 3: T-Shaped Design
Figure 4: Rectangular Shaped Design
Figure 5: Circular Shaped Design (Kittenbot.com)
Table 1: Comparison of the Designs

After considering pros and cons of each chassis design, we designed to move forward with the rectangular shape for our robot’s chassis design.

Regarding the material of the chassis, plywood and acrylic were taken into consideration. However, we chose to proceed with plywood because of its affordability and high availability. The plywood was drilled to make the cutouts, mounting holes for the M2 screws and hacksaw bladed to be cut to shape. The chassis was then manually painted in green to give an aesthetic finish.

Given below is the finalized chassis design for the robot.

Figure 6: Cut Plywood Chassis Platform
Figure 7: Wheels and Motor Mounting Assembly

3. Final Chassis Assembly

For the final assembly of the robot there were two configurations:

· The first option being placing the PCB on top of the chassis at an offset so that the sensors could detect the lines without any interferences.

· The second option being mounting the PCB directly above the chassis, and having cut-outs on the chassis for each sensor.

Out of the above two configurations, in order to make sure the compact design and proper weight distribution on the overall design, we decided to move forward with the second option. Given below is the final assembly.

Figure 8

4. Schematic Developing, Testing, Simulating and PCB Designing

Schematic Developing

1) Motor Driver and the Voltage Regulator Setup

Any designing 1st starts from a basic skeleton, likewise, for PCB designing a block diagram is necessary. Including all the parts of a line follower, a block diagram needs to be constructed as the 1st step. This project was chosen to be started from the schematic of the desired PCB.

Frequently downloading the respective datasheets of the components involved in the planned circuitry and constant reference to the datasheet during connections of them makes the connection task easier. This is due to the detailed description of the functionality of each pin and their characteristics being technically written in a standard datasheet. A recommended source to extract datasheets is Alldatasheet.com.

As the 1st step, the schematic of the L293D motor driver circuitry was developed. Which was followed by the voltage regulator circuit which is needed to convert the 12V input to a 5V input to be supplied as the ideal logic voltage Vss.

Figure 9: Motor Driver and the Voltage Regulator Schematic

According to the above circuitry the switch connection was placed in the 12V line, a latching on/off switch connection was necessary because the circuit should remain switched on until the switch Is pressed again to switch it off. As per the motor connections, according to the datasheet enable pins involve in generation of PWM signals to the motor according to the code pattern fed to an MCU (in this case ATMega328P). Enable 1 and Enable 2 were given to two PWM pins of the ATMega328P chip used. Similarly, the input pins (IN1, IN2, IN3, IN4 — usually controlling the torque direction of the motors) of the motor driver were connected to the respective pins to the ATMega328P chip.

Vs to the 12V and the Vss to the 5V regulated by the LM7805 regulator IC. The A outs and B outs are connected directly to the motor connector pins according to the polarities (positive end and the negative end).

2) The Programming Setup

This setup comprises the headers for the FTDI connection, the ATMega328P chip, 16MHz Crystal Oscillator, ¼ Watt Resistors and the respective capacitors. This setup makes it easier for the ATMega328P chip to programmed via Arduino IDE rather than undergoing the hassles of C programming. Choosing Arduino IDE over C gives a more beginner friendly approach to C programmed robot.

Out of the 6 pins in the FTDI module the CTS pin remains unconnected as it serves no purpose for the programming setup. Pins like CTS and RTS work on helping the hardware flow control. The CTS, Clear to Send pin is usually used for the purpose of maintaining a smooth data flow between the data transmitting and the receiving end. This helps in preventing an overwhelming flow of data in the receiving end and makes sure the data is transferred to the receiving end only when the receiver is ready to accept the rush of new data packets. This usually works in pair with RTS, Request to Send. RTS signal works from the transmitting end, when the data is ready to be sent from the transmitting end.

In this programming setup, given the ATMega328P chip’s programming principles, a hardware flow control is not necessarily needed because the bootloader communication protocols are already adapted to handle slower rate data flow without the need for the involvement of CTS. DTR, Data Terminal Ready is another type of pin which communicates with the microcontroller to reset itself, before the in rush of data. The TX and RX on the other hand is used to for bidirectional communication in-between the FTDI and the ATMega controller, implementing an effective USART protocol.

16MHz crystal oscillator on the other hand helps in generating accurate clock signals to carry out certain tasks as planned. This external crystal oscillator is connected to the XTAL1 and XTAL2 as the input and output terminal of the crystal. This crystal oscillator has a quartz crystal with a resonant frequency of 16MHz. Though there are many other frequency types the 16MHz external oscillator was installed due to its compromised performance in terms of speed and power consumption along with its suitability for the FMLFR project.

Finally, the power pins were connected according to the below shown schematic.

Figure 10

Above shows the programming setup which was followed, as shown two 22pF capacitors are used to compensate the load capacitance and ensure a correct conditioned stable frequency output is received from the oscillators. This makes sure to cancel noise and the jittery nature of the crystal oscillations usually.

The rest of the capacitors on display above, are also primarily focusing on the stability of the signals through the respective lines like DTR and Vcc. The 100nF acts as a body which triggers a brief pulse in order to create a pulse for the resetting of the ATMega chip. The 100uF capacitor is important in-between the Vcc and the GND line as shown above to help in avoiding sudden voltage spike/fluctuation while powering the circuit.

3) The IR Array Setup

The IR circuit was chosen to be carefully crafted given it is the most crucial part for the programme to start with. The IR setup for FMLFR was chosen to be digital and was assembled portion by portion from scratch. The sensing unit, which was the TCRT5000 was separately procured for this setup.

Figure 11: A TCRT5000 unit

Due to the digital setup being chosen, LM393 chip was procured to build the IR setup. LM393 was chosen over LM311 or any other array line hunting sensors due to the ease of PCB assembly and in hopes of reducing the overall PCB size as much as possible. LM393 gave access to connect 2 TCRTs per chip with just 8 pins per chip. LM311 had 8 pins in a chip which supported the connection of only one TCRT5000 unit. The line hunting array on the other hand was not suiting the planned overall chassis design hence, it was pushed out of the consideration list.

Altogether five TCRT5000 units were chosen to be assembled. This in turn led to a circuitry comprising of 3 LM393 chips, 15 resistors (5*10K, 5*220 ohm,5*150 ohm) and 5 of 10K presets.

Due to predicted uncertainties of a digital setup an analog setup was also built parallel to it.

Figure 12
Figure 13
Figure 14

The standby analog design was similar setup configurations with small changes in the IR setup and the pinouts used form the ATMega chip.

Figure 15
Figure 16: Analog GPIO setup

The above were the significant changes in the analog version of FMLFR.

The motor input and PWM pins were carefully connected apart from the IR signal pins S1 to S5. The input pins ADIR1, ADIR2, BDIR1 and BDIR2 were fed to the normal digital GPIO pins and the PWM pins were designated to pins with PWM signal abilities.

Before actually implementing the whole schematic setup there were several milestones ticked. This includes the simulation, the breakout board setup and surety test/trial before implementing the setup as a schematic on Easy EDA.

4) The GPIO pins setup

Figure 17:

The above reference image from elecrom.com was a major helping hand to picture where are the actual ATMega328P connected and help in knowing which pin needs to be defined during programming.

According to the above reference and the below developed schematic the ATMega328P pins were assigned with the desired digital input pins.

Figure 18: Digital GPIO Setup

Testing

This is one of the most important stages in order to make sure if the theoretically constructed schematic works well in reality or not. The group followed this path so any minor adjustments could be redone via easy EDA if there’s already a theoretically generated schematic framework.

This stage had 3 major testing stages,

1) ATMega328P Programming Setup test

2) Motor circuit test

3) IR circuit test

1) The ATMega328P Programming Setup Test

The setup was replicated on a breakout board and an example code was uploaded to blink the LED on the FTDI.

const int LED_BUILTIN = 8

void setup() {
pinMode(LED_BUILTIN, OUTPUT);
}

void loop() {
digitalWrite(LED_BUILTIN, HIGH);
delay(1000);
digitalWrite(LED_BUILTIN, LOW);
delay(1000);
}

The above built in LED code example was selected from the “Examples” option under “Files” on Arduino IDE in order to check if the LED pin of the ATMega328P chip makes the external LED setup blink with 1000ms interval, proving that the setup is functioning as expected.

In this case Pin 8 was defined as the LED_BUILTIN pin according to the ATMega328P chip’s PB0 pin (14th pin) configuration.

Figure 19: Switch On 1000ms
Figure 20: Switch Off 1000ms

The above images show 1000ms of switching off and 1000ms of switching on of the external LED.

2) Motor Circuit Test

The previously shown motor driver circuit was again replicated on a breakout board. Shortly after the replication, the 2 motors were connected to the AOut and BOut pins (the 4 output pins) were connected to the motors with the correct positive and negative terminals.

The signals were given to the motor driver chip via an Arduino Uno board during the testing. Below shown is an image of the simulation conducted before finalizing the schematic.

Figure 21: L293D Simulation Setup

The code uploaded to the Arduino Uno was to make the motor rotate in clockwise direction twice and then anticlockwise direction twice with increasing speed of interval 10 PWM value on each iteration.

// Define motor control pins
const int enablePin = 5; // PWM pin to control motor speed
const int in1Pin = 2; // Control pin 1
const int in2Pin = 3; // Control pin 2

void setup() {
// Initialize motor control pins as outputs
pinMode(enablePin, OUTPUT);
pinMode(in1Pin, OUTPUT);
pinMode(in2Pin, OUTPUT);

// Set initial motor direction (clockwise or counterclockwise)
digitalWrite(in1Pin, LOW);
digitalWrite(in2Pin, HIGH);
}

void loop() {
// Run the motor with varying speeds
for (int speed = 0; speed <= 255; speed += 10) {
// Set motor speed
analogWrite(enablePin, speed);
delay(500); // Wait for a while
}

// Stop the motor
analogWrite(enablePin, 0);
delay(1000); // Wait before reversing the motor

// Change motor direction
digitalWrite(in1Pin, !digitalRead(in1Pin));
digitalWrite(in2Pin, !digitalRead(in2Pin));

// Run the motor in the opposite direction with varying speeds
for (int speed = 0; speed <= 255; speed += 10) {
// Set motor speed
analogWrite(enablePin, speed);
delay(500); // Wait for a while
}

// Stop the motor
analogWrite(enablePin, 0);
delay(1000); // Wait before changing direction again
}

3) IR Circuit Test

This IR circuit test was one of the most crucial feat achieved in this project apart from the overall project coding logics. IR circuitry is the whole sensing unit of the robot, without its smooth functioning, passing the other hurdles is a difficult or rather an impossible task.

Figure 24

It was decided to use the below digital circuit for the IR setup, basically the KY-033 TCRT5000 module due to its ease of building and due to its usage of lesser components.

Figure 25: Simulation with LM393

The circuit was later developed into a simulation model, to check its reliability and accuracy.

The simulation gave better results but the breakout board replication gave no expected results. This proves of how simulation could be uncertain sometimes and it is best to build these simple setups on a breakout board before further implementation.

Preceding this first trial, it was decided to try an analog circuit with the LM358 OpAmp IC and the normal IR LED and Photo Diode set (apart from TCRT5000). Below was the reference schematic built after careful analysis of the datasheet of the OpAmp IC,

Figure 26: LM358 Pinouts
Figure 27: Analog OpAmp IC Circuit

Below was the working replication on the breakout board,

Figure 28

Following this assurance, another version of the analog circuit was found. This setup was the simplest setup due to the less number of components at use and no chips being used. This simple setup shown below was the IR setup used for the analog version of the FMLFR PCB.

Figure 29

After witnessing both analog circuitries give a smooth analog transition for the IR reflection, the group was eager to try another digital setup. This time the digital setup was following a different schematic. This LM393 based schematic was the finalized IR circuitry for the digital version of the FMLFR PCB.

Figure 30

Though this circuit is reliable in terms of pinout connections, it might give no results if the pins of the TCRT5000 aren’t connected correctly. This may not necessarily be an error of the engineer who develops the circuit, it also could be a manufacturing/placement fault of the TCRT pins. It is always best to remove the plastic casing to test the LED and the transistor of the TCRT one by one to rearrange the pins in the right way within the TCRT’s plastic casing.

PCB Designing and Assembly

This stage of the project was the most time consuming process.

With all the components being through-hole components in this version of FMLFR, the schematic was converted into a PCB layout.

With track width of 0.3mm for power lines and 0.2mm for the signal lines the PCB was routed in 2 layers successfully. The vias used in this PCB are 0.3mm in diameter with 0.2mm drill diameter.

Below shown is a proof for the design rule settings,

Figure 31

The top and the bottom layer was covered with a GND copper area for the ground pads to connect without any direct routing. This could be done by clicking the below blue circled icon (Copper Area icon) and drawing the outline around the area which is needing the copper area plane and right click to lock the copper area around the desired plane of the PCB.

Figure 32
Figure 33

Below shown is a 2D view of the digital IR FMLFR PCB,

Figure 34: Top Side
Figure 35: Bottom Side

The PCB was initially a rectangle which was later curved at the front according to the desired mechanical design. The special spacing on the either side of the motors were for the mountings to be placed in order to stack up the PCB on top of the decided chassis platform.

After the routing and the final checking of the PCBs (digital and analog). The Gerber files were saved and submitted to JLCPCB for manufacturing processes to start. Lead-based HASL (hot air solder leveling) finish was chosen for the PCB for a smoother finish, easier solderability and it was a compromised choice for a simple line following PCB like FMLFR’s. Though a long run disadvantage could emerge in terms of high humidity and high temperature conditions, for the current use a Lead based HASL finish is acceptable. Lead-free HASL could be an option if the developer is more likely to prefer an environmental friendly finish.

After the procurement of the unassembled PCBs, a brief connectivity test was held using the multimeter, after making sure the connections secured carefully, the components were soldered according to the plotted footprints. At the end, the voltage regulator was also fitted with a small heat sink along with a mica sheet. Below shows the completed setup,

Figure 36: Soldered PCB

The TCRTs were decided to be soldered to a vero board setup. This was considering the length of the TCRT pins under use. In order to bring the TCRTs as close as possible to the ground while the pins being able to fit to the TCRT connection pads on the PCB via soldered jumper cables.

Another major point while assembling was, usage of IC bases in place of directly soldering the chips to the PCB. It is always advised to do so because it is highly risky for the whole PCB setup in case of a chip failure or a PCB setup failure/short circuits. Usage of IC bases would help easy replacement of chips under those circumstances without actually undergoing the hassle of de-soldering the chip, making the setup untidy and less reliable.

At the end, the setup was connected to the 12V supply to check if the green LED lit up, indicating a proper functioning of the voltage regulator circuit. After a successful attempt the PCB setup was glued on top of the 2mm long mounting nuts. The power regulator also comes with a boost converter to convert the 7.4V coming from the two 3.7V lithium batteries into 12V needed by the regulator. This booster lays beneath the PCB on top of the chassis platform just like the two batteries.

Figure 37

5. SOFTWARE CONFIGURATION

Line followers are typically coded with very similar patterns no matter the design. There should always be a logic which connects the the IR sensor readings and the way motor adjusts itself on the track to follow the line efficiently.

Below shows the roughly observed TCRT placement during the scenarios of forward run, right turned run and left turned run.

Figure 38: TCRT Placements

In this particular scenario, due to the track’s unstable nature or randomness, a control algorithm was also decided to be implemented as a part of the basic line following code snips.

There were two control algorithms which seems to suit this particular functionality. They are, PID control algorithm and Fuzzy logic algorithm. Both of them are possible approaches to this coding but Fuzzy logic is more linguistical and complex to be implemented in such a short time. Due to the simplicity and the most required functionalities of FMLFR a PID control algorithm was thought to be incorporated to the code.

Below shows a simple software flowchart to visualize the stages underwent during the firmware development for FMLFR on Arduino IDE.

Figure 39: Simplified Version of the Software Flowchart for Understanding
#define TCRT1 8
#define TCRT2 9
#define TCRT3 10
#define TCRT4 11
#define TCRT5 12
#define A_PWM 5 //left motor speed control
#define B_PWM 6 // right motor speed control
#define A_DIR2 3//left motor input
#define B_DIR2 7//right motor input

//define motor max and operating speed
int MAX_SPEED = 250;
int MotorBasespeed = 100;

int Lmotorspeed = 0;
int Rmotorspeed = 0;
int IR_val[5] = {1,1,1,1,1};
int IR_weights[5] = {-20, -10, 0, 10, 20};


// PID controller
float Kp = 5.5;
float Ki = 0;
float Kd = 10;

float error = 0, P = 0, I = 0, D = 0, PID_value = 0;
float previousError = 0, previousI = 0;


void PID_control();
void set_speed();
void forward();
void turnRight();
void turnLeft();
void Stop();

void setup () {
Serial.begin(9600);
pinMode (TCRT1, INPUT);
pinMode (TCRT2, INPUT);
pinMode (TCRT3, INPUT);
pinMode (TCRT4, INPUT);
pinMode (TCRT5, INPUT);
pinMode (A_PWM, OUTPUT);
pinMode (B_PWM, OUTPUT);
pinMode (A_DIR2, OUTPUT);
pinMode (B_DIR2, OUTPUT);
digitalWrite (A_PWM, HIGH);
digitalWrite (B_PWM, HIGH);
delay(1000);}


void loop() {
read_IR();

if((digitalRead(TCRT1) == 1) && (digitalRead(TCRT2) == 1) && (digitalRead(TCRT3) == 1) && (digitalRead(TCRT4) == 1) && (digitalRead(TCRT5) == 1)){

Stop(); //if Right Sensor and Left Sensor are at Black color then it will call Stop function
while(1){}
}

if(((digitalRead(TCRT1) == 1) && (digitalRead(TCRT2) == 1) && (digitalRead(TCRT3) == 0) && (digitalRead(TCRT4) == 1) && (digitalRead(TCRT5) == 1))|| ((digitalRead(TCRT1) == 0) && (digitalRead(TCRT2) == 0) && (digitalRead(TCRT3) == 0) && (digitalRead(TCRT4) == 0) && (digitalRead(TCRT5) == 0))){

forward();
}
//if Right Sensor and Left Sensor are at White color then it will call forward function

if((digitalRead(TCRT1) == 1) && (digitalRead(TCRT2) == 1) && (digitalRead(TCRT3) == 1) && (digitalRead(TCRT4) == 0) && (digitalRead(TCRT5) == 1)){
turnRight();
}
//if Right Sensor is Black and Left Sensor is White then it will call turn Right function

if((digitalRead(TCRT1) == 1) && (digitalRead(TCRT2) == 0) && (digitalRead(TCRT3) == 1) && (digitalRead(TCRT4) == 1) && (digitalRead(TCRT5) == 1)){
turnLeft();
}
//if Right Sensor is White and Left Sensor is Black then it will call turn Left function

PID_control();
set_speed();
}



void read_IR(){
IR_val[0] = digitalRead(TCRT1);
IR_val[1] = digitalRead(TCRT2);
IR_val[2] = digitalRead(TCRT3);
IR_val[3] = digitalRead(TCRT4);
IR_val[4] = digitalRead(TCRT5);

}


void forward(){ //forward
analogWrite(A_PWM, MAX_SPEED);
analogWrite(B_PWM, MAX_SPEED);

digitalWrite(A_DIR2, HIGH); //left motor
digitalWrite(B_DIR2, HIGH);} //right motor


void turnRight(){ //turnRight
analogWrite(A_PWM, 0);
analogWrite(B_PWM, 100);

digitalWrite(A_DIR2, LOW); //left motor
digitalWrite(B_DIR2, HIGH);} //right motor


void turnLeft(){ //turnLeft
analogWrite(A_PWM, 100);
analogWrite(B_PWM, 100);

digitalWrite(A_DIR2, HIGH); //left motor
digitalWrite(B_DIR2, LOW);} //right motor


void Stop(){ //stop
analogWrite(A_PWM, 0);
analogWrite(B_PWM, 0);

digitalWrite(A_DIR2, LOW); //left motor
digitalWrite(B_DIR2, LOW); //right motor
}

void set_speed(){
analogWrite(A_PWM, Lmotorspeed);
analogWrite(B_PWM, Rmotorspeed);
}


void PID_control(){

error = 0;

for (int i = 0; i < 6; i++)
{
error += IR_weights[i] * IR_val[i];
}


error = 0;
P = error;
I = I + error;
D = error - previousError;

PID_value = (Kp * P + Ki * I + Kd * D);

Lmotorspeed = MotorBasespeed - PID_value;
Rmotorspeed = MotorBasespeed + PID_value;

if (Lmotorspeed < 0)
{
Lmotorspeed = 0;
}
if (Rmotorspeed < 0)
{
Rmotorspeed = 0;
}
if (Lmotorspeed > MAX_SPEED)
{
Lmotorspeed = MAX_SPEED;
}
if (Rmotorspeed > MAX_SPEED)
{
Rmotorspeed = MAX_SPEED;
}


}

6. TEST RUN, TRIAL AND CHALLENGES

The robot was finally assembled completely with the TCRT setup and mounted safely on the constructed Plywood chassis, as shown earlier.

The switch was then checked for its functioning, due to the green LED lighting up as soon as the switch was pressed, it’s a more than enough indication that the voltage regulator setup is working.

Then, the chips were placed on the IC bases in the correct orientations. During this process, while the switch is on the red IR LEDs lit up according to the surface they were facing. The presets were then adjusted to increase the sensitivity of the TCRTs respectively.

On black surface the red indicator LEDs switched off and on a white surface the LED switched on. This represents a smooth functioning of the IR setup as well.

During this test the major challenge faced was the power circuit draining the batteries. To avoid this, it was made sure that the input voltage is as high as possible for the booster setup to easily step the already higher voltage to a 12V out supply.

The FTDI setup was next tested and the ATMega328P chip was flashed with the test built-in LED code. This time a communication error was faced whilst trying to upload the code using the FTDI setup on the PCB. This was not further risked, therefore, the breakout board setup was planned to be used to flash the ATMega328P chip. Immediately after following this, the error persisted.

It was then noted that, the FTDI setup could be more sensitive than expected if the components aren’t mount properly on the dot board with the properly functioning components. After so many attempts to rebuild the similar circuit, the FTDI setup started to function as expected. Persistence is key! The error was troubleshot to be concluded as a simple pin connectivity issue.

After uploading the code, the main PID line following code given in the above software configuration was uploaded. The motors did not turn in the beginning, after further troubleshooting it was found that one of the motors had a gear defect which was holding the friction up high making it impossible for the motor to generate the torque.

The motors were later replaced and tried again. This time it worked but the battery drain was high.

Another PCB was re-soldered to try the setup again. The ATMega328P chip was flashed again with the developed code.

It was concluded that the PCB soldering and power input were the most crucial turning points in trials/ test runs. During the 2nd iteration of code uploading it was noted that, the ATMega328P should be boot loaded at least for once in order to avoid any FTDI communication failures while uploading the code.

Another issue which came up during the development of the PCB assembly was the malfunctioning of the IR circuitry. This was diagnosed to be an issue with the ways the emitter LED and the phototransistors were placed within the plastic casing. As discussed earlier, it is always best to either purchase TCRTs with longer/ untrimmed terminal pins or to remove the plastic casing to test the emitter and the transistor individually to navigate the cathode-anode and the collector-emitter.

Next, the power on/off switch was found be having the footprint of a normally opened, momentary push button. This was rectified by taking the two ends of power lines involved with switch to another latching torch switch which was glue gunned to the chassis platform.P

During the final test run the main problem was diagnosed to be in the motor driver circuitry configuration. This connection is likely short-circuiting due to some error in routing the PCB assembly. This has lead to the drastic battery drainage from the 1st test run. As of currently, due to the very short amount of time to route and remanufacture the PCB it was decided to use new batteries. Following this it was concluded to try to demonstrate at least the IR logic and the motor turning with the PCB.

7. RESULTS AND DISCUSSION

  • This project acted as display of a successful mini line following robot with its physical specifications and designing.
  • The schematics followed were all verified to be correct except the routing of the PCB which lead to a short circuit at the Vs/12V line of the motor circuitry.
  • The plan by which the code was developed was also a successful attempt in making the robot function as expected at least with the TCRT and the motor turning logic.
  • The design specifications were carefully crafted around the statement of “fast” and “mini” line follower. This almost 120mm by 120mm chassis and almost 97.5mm by 70.5mm PCB suited the “mini” requirement and the 300rpm speed of the chosen N30 motors along with a compromised weight (within 1kg) of the robot contributed to the “fast” requirement according to F=m*a.

8. CONCLUSION

Overall, the project FMLFR is expected to be continued in order to rectify the short circuit happening with the motor circuitry and the whole circuit setup is planned to be rebuilt again from the breakout board stage in order to understand all the possible hindrance of the circuit from 100% successful implementation.

The current state of the FMLFR as of May 19th 2024 is moderately satisfying in terms of IR circuitry and microcontroller setup. Line followers could actually take several forms, further research and development could be done to reach the most ideal fast and mini line following robot.

— — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — — —

Authors:

, , (under )

--

--