This circuit is designed to control a mobile robot equipped with a servo motor, two sets of motor and wheels, an HC-SR04 ultrasonic sensor, and an L298 Dual H Bridge Motor Speed Controller. The brain of the robot is an Arduino UNO, which is interfaced with an Arduino Sensor Shield v5.0 for easy connection of peripherals. The ultrasonic sensor is mounted on the servo motor for scanning the environment. The L298 controller drives the motors, allowing for speed and direction control. A rocker switch is used to control the power from a 3xAA battery pack to the system.
#include <Servo.h>
Servo servo;
// Ultrasonic Module pins
const int trigPin = 13;
const int echoPin = 12;
// Servo motor that aims ultrasonic sensor
const int servoPin = 11;
// Motor control pins: L298N H bridge
const int enAPin = 6; // Left motor PWM speed control
const int in1Pin = 7; // Left motor Direction 1
const int in2Pin = 5; // Left motor Direction 2
const int in3Pin = 4; // Right motor Direction 1
const int in4Pin = 2; // Right motor Direction 2
const int enBPin = 3; // Right motor PWM speed control
enum Motor { LEFT, RIGHT };
// Set motor speed: 255 full ahead, -255 full reverse, 0 stop
void go(enum Motor m, int speed) {
digitalWrite(m == LEFT ? in1Pin : in3Pin, speed > 0 ? HIGH : LOW);
digitalWrite(m == LEFT ? in2Pin : in4Pin, speed <= 0 ? HIGH : LOW);
analogWrite(m == LEFT ? enAPin : enBPin, speed < 0 ? -speed : speed);
}
// Initial motor test: left motor forward then back, right motor forward then back
void testMotors() {
static int speed[8] = {128, 255, 128, 0, -128, -255, -128, 0};
go(RIGHT, 0);
for (unsigned char i = 0; i < 8; i++) {
go(LEFT, speed[i]);
delay(200);
}
for (unsigned char i = 0; i < 8; i++) {
go(RIGHT, speed[i]);
delay(200);
}
}
// Read distance from the ultrasonic sensor, return distance in mm
unsigned int readDistance() {
digitalWrite(trigPin, HIGH);
delayMicroseconds(10);
digitalWrite(trigPin, LOW);
unsigned long period = pulseIn(echoPin, HIGH);
return period * 343 / 2000;
}
#define NUM_ANGLES 7
unsigned char sensorAngle[NUM_ANGLES] = {60, 70, 80, 90, 100, 110, 120};
unsigned int distance[NUM_ANGLES];
// Scan the area ahead by sweeping the ultrasonic sensor
void readNextDistance() {
static unsigned char angleIndex = 0;
static signed char step = 1;
distance[angleIndex] = readDistance();
angleIndex += step;
if (angleIndex == NUM_ANGLES - 1) step = -1;
else if (angleIndex == 0) step = 1;
servo.write(sensorAngle[angleIndex]);
}
// Initial configuration
void setup() {
pinMode(trigPin, OUTPUT);
pinMode(echoPin, INPUT);
digitalWrite(trigPin, LOW);
pinMode(enAPin, OUTPUT);
pinMode(in1Pin, OUTPUT);
pinMode(in2Pin, OUTPUT);
pinMode(in3Pin, OUTPUT);
pinMode(in4Pin, OUTPUT);
pinMode(enBPin, OUTPUT);
servo.attach(servoPin);
servo.write(90);
go(LEFT, 0);
go(RIGHT, 0);
testMotors();
// Scan the surroundings before starting
servo.write(sensorAngle[0]);
delay(200);
for (unsigned char i = 0; i < NUM_ANGLES; i++) {
readNextDistance();
delay(200);
}
}
// Main loop: check if something is too close
void loop() {
readNextDistance();
unsigned char tooClose = 0;
for (unsigned char i = 0; i < NUM_ANGLES; i++) {
if (distance[i] < 300) {
tooClose = 1;
}
}
if (tooClose) {
// Something's nearby: back up left
go(LEFT, -180);
go(RIGHT, -80);
} else {
// Nothing in our way: go forward
go(LEFT, 255);
go(RIGHT, 255);
}
// Check the next direction in 50 ms
delay(50);
}
The provided code is for an Arduino UNO microcontroller. It includes a library for controlling the servo motor and defines pins for interfacing with the ultrasonic sensor and the motor controller. The code contains functions to control the motors, read distances from