Part 2 - Adding Obstacle Detection and Avoidance To The Mobile Robot Madibabaiasl - Mechatronics-Course Wiki GitHub
Part 2 - Adding Obstacle Detection and Avoidance To The Mobile Robot Madibabaiasl - Mechatronics-Course Wiki GitHub
In part 1 of the project, you understood the basic motion control of your wheeled mobile robot and you have calibrated it for Pages 15
precise distance, turn angle, and variable linear and rotational speeds. In labsson 9, you learned about ultrasonic sensors
and you calibrated and denoised your own ultrasonic sensor. Find a page…
In this part, you will use your knowledge of ultrasonics sensors and the basic motion control of the robot to give the Home
obstacle detection and avoidance ability to your mobile robot. We will use a servo motor to turn/sweep the ultrasonics
sensor, so let's start by learning about servo motors first. Labsson 1: Electricity Fundamentals - …
Some of cool implementations by students for this part: Labsson 2: Resistors, Variable Resistor…
https://github.com/madibabaiasl/mech
A pulse width of 1.5 milliseconds typically corresponds to the center position of the servo motor (90 deg).
A pulse width less than 1.5 milliseconds rotates the shaft in one direction (e.g., counterclockwise).
A pulse width greater than 1.5 milliseconds rotates the shaft in the opposite direction (e.g., clockwise).
First wire your servo motor to Arduino. Make sure to connect the signal wire to a PWM pin, and two others to GND and
5v pins of the Arduino.
Then upload the following code to your Arduino board and explain what happens:
void setup() {
// Attach the servo to the pin
servoMotor.attach(servoPin);
}
void loop() {
// Move the servo to the 0-degree position
servoMotor.write(0);
delay(1000); // Wait for 1 second
Now, choose the Sweep code from the Examples in the Arduino IDE and upload it to your Arduino board to see how the
servo motor can be programmed to move back and forth across its range automatically.
We need to create a code for wandering around with the mobile robot without hitting obstacles. This requires creating
separate modular functions: car motion module (that you already implemented in part 1), ultrasonic module (which is largely
done in labsson 9), servo scan module, setup module and loop module.
#include <Servo.h>
// Driving settings
int AIN1 = 7;
int BIN1 = 8;
int PWMA = 5;
int PWMB = 6;
int STBY = 3;
// Scanner settings
Servo myservo; // servo object
const int servoPin = 10; // servo pin (look at where the wires from servo go on the shield)
int rotation_delay = 2; // Servo scanning delay in milliseconds
const int echoPin = 12; // Echo pin connected (verify this by checking the pins on the shield)
const int trigPin = 13; // Trig pin connected (verify this by checking the pins on the shield)
const float m = [include your own from calibration]; // Linear fit slope (following calibration of ultrasonic sensor)
const float b = [include your own from calibration]; // Linear fit offset (following calibration of ultrasonic sensor)
const float max_dist = 60; // Maximum detectable distance by ultrasonic sensor (in cm for my robot). Make sure to adju
Setup Module
The setup module sets the pin modes, initializes the car state to be stationary and brings the servo motor to the default
position at 90 degrees (facing forward direction), as follows (again this is a quick code to just get inspiration from):
void setup() {
// Driving setup
pinMode(AIN1,OUTPUT);
pinMode(BIN1,OUTPUT);
pinMode(PWMA,OUTPUT);
pinMode(PWMB,OUTPUT);
pinMode(STBY,OUTPUT);
digitalWrite(STBY,HIGH);
stopCar();
// Scanner setup
myservo.attach(servoPin); // Attach the servo to the pin
myservo.write(90); // Default servo position which is the forward direction
pinMode(trigPin, OUTPUT); // Attach ultrasonic trigger pin
pinMode(echoPin, INPUT); // Attach ultrasonic echo pin
}
Ultrasonic Module
We have learnt how to use the ultrasonic sensor in labsson 9, starting with calibration and ending with smoothening. Now turn
the code that you wrote for that labsson into a function, where the function should return the sensor reading to the main
loop function. The calibrated sensor reading will be good enough for turning around obstacles. The skeleton of this function
is something like following:
float Ultrasonic() {
return calibrated_distance;
}
I again wrote a quick code below for this part but this code is not optimal. Get inspiration from this code and make it more
optimal:
int ServoScan() {
// Return the servo to zero position
myservo.write(0); delay(10);
// Map the area till you find a direction with the furthest obstacle ahead
// the step size here is 10. play around with it to find an optimal step size
int angle; int optimal_angle = 0; float optimal_dist = 0;
for (angle = 0; angle <= 180; angle += 10) {
// Rotate
myservo.write(angle); // Send the new angular command
delay(rotation_delay); // Adjust the delay for the desired speed
// Scan the direction and declare new distance as optimal if met with least obstacles
float dist = Ultrasonic(); // Capture a new distance reading
if (dist > optimal_dist || (dist==optimal_dist && abs(angle-90)<abs(optimal_angle-90))){
optimal_dist = dist; // The new discovered distance is optimal distance
optimal_angle = angle;
}
}
myservo.write(90); // Back to default servo position
return optimal_angle;
}
Main Module
The main module is the void loop function. As explained before, the car would continuously monitor the ultrasonic sensor's
output. If the output indicates an obstacle, the car would stop, call the ServoScan function and turn around to achieve the
optimal angle. Following the turning around period, the car would move forward again. The following is an skeleton code to
start with. Note that you should change this code and make it more optimal. The numbers for distance, angle, and speed
should also change based on your calibration (they are random numbers):
void loop() {
// Mission code (runs continuously)
float dist = Ultrasonic();
Instead of moving a large distance at once, you could make the robot move shorter distances and check for obstacles
more frequently. This allows the robot to react more promptly.
Modify the forward function to intermittently check for obstacles as it moves. This can be done by incorporating checks
after moving a small fraction of the desired distance. Add this to the end of your forward function:
// Explanation: This line calculates the total time (in milliseconds) it should take for the
// robot to move the specified distance at the given speed.
long time_to_move = distance / speed * 1000.0; // Total time to move the specified distance
// the following line captures the start of the movement
// This records the current time (in milliseconds since the program started)
// right before the robot begins to move. This timestamp is used as
// a reference point to measure elapsed time.
long start_time = millis();
// the following line defines how often (in milliseconds) the robot should check
// for obstacles in its path. A shorter interval means more frequent checks.
long check_interval = 10; // Time interval to check for obstacles in milliseconds.
// This while loop runs as long as the elapsed time since start_time is less than time_to_move.
// It ensures the robot continues its intended movement for the calculated duration unless interrupted by detecting
while (millis() - start_time < time_to_move) {
// inside the loop, the Ultrasonic() function checks the distance to the nearest obstacle.
// If this distance is less than or equal to max_dist (the threshold distance at
// which an obstacle is considered too close), the stopCar() function is called to halt
// the robot immediately, and the function exits (return).
if (Ultrasonic() <= max_dist) {
stopCar();
return; // Stop moving if an obstacle is detected within the maximum detectable distance
}
// After each obstacle check, the program pauses for check_interval milliseconds
// (set to 10 ms above) before checking again. This brief delay controls how frequently the robot checks for o
delay(check_interval); // Wait for the check interval before checking again
}
Good luck!
© 2025 GitHub, Inc. Terms Privacy Security Status Docs Contact Manage cookies Do not share my personal information