Module 13: Final Project: Autonomous Navigator
Level: 🟢 Beginner Board: Arduino Uno + full robot Prerequisites: Module 12 Estimated time: 90–120 minutes Goal: Build a complete autonomous navigator that combines all course skills into a single tested program.
What You'll Learn
By the end of this module you will have run a defined obstacle course in autonomous mode and used Serial Monitor data to improve your robot's performance across two timed runs. You will produce a one-page documentation package covering your bill of materials, calibration values, known limitations, and engineering reflections.
This is the final build module. You'll take everything from the course: calibrated drivetrain, tuned sensor, state machine, unified control, and produce a polished, documented robot that can run a defined challenge course reliably. The goal is not a new feature. The goal is a robot that works, repeatably, and that you can explain fully.
13.1 The final challenge
The course robot must complete the Navigator Challenge: navigate a defined obstacle course from start to finish, in autonomous mode, without human intervention, within a time limit.
Course definition:
<svg viewBox="0 0 760 340" width="100%" xmlns="http://www.w3.org/2000/svg">
<!-- Course boundary -->
<rect x="40" y="20" width="680" height="300" rx="4" fill="#f5f2eb" stroke="#3d3c38" stroke-width="2"/>
<text x="380" y="14" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#888">3m × 2m COURSE AREA</text>
<!-- Start zone -->
<rect x="50" y="270" width="80" height="40" rx="2" fill="#d8f0e5" stroke="#1a6b4a" stroke-width="1.5"/>
<text x="90" y="287" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">START</text>
<text x="90" y="302" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3d28">send 'M' here</text>
<!-- Finish zone -->
<rect x="630" y="270" width="80" height="40" rx="2" fill="#daeaf5" stroke="#1f4d8c" stroke-width="1.5"/>
<text x="670" y="287" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">FINISH</text>
<text x="670" y="302" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3060">robot must reach</text>
<!-- Obstacles -->
<!-- Box obstacle 1 -->
<rect x="200" y="180" width="60" height="60" rx="2" fill="#3d3c38"/>
<text x="230" y="215" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#edeae0">box</text>
<!-- Box obstacle 2 -->
<rect x="400" y="100" width="60" height="60" rx="2" fill="#3d3c38"/>
<text x="430" y="135" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#edeae0">box</text>
<!-- Chair leg obstacle -->
<circle cx="320" cy="240" r="12" fill="#3d3c38"/>
<text x="320" y="265" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">chair leg</text>
<!-- Narrow gap -->
<rect x="520" y="20" width="20" height="120" rx="1" fill="#3d3c38"/>
<rect x="580" y="20" width="20" height="120" rx="1" fill="#3d3c38"/>
<text x="550" y="90" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">30cm</text>
<text x="550" y="102" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">gap</text>
<!-- Suggested path (dashed) -->
<path d="M130 290 Q130 240 180 220 Q260 180 360 200 Q440 220 480 180 Q520 140 540 160" fill="none" stroke="#c8b400" stroke-width="1.5" stroke-dasharray="6 4" opacity=".7"/>
<text x="360" y="334" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#888">one possible path — robot finds its own</text>
<!-- Labels -->
<text x="480" y="36" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">optional:</text>
<text x="480" y="48" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">narrow gap</text>
<text x="480" y="60" font-family="Manrope,sans-serif" font-size="8" fill="#888">(extra credit)</text>
</svg>
Fig 13.1 - Navigator Challenge layout. 3 m × 2 m floor area, three obstacles (two flat-sided boxes, one round chair leg), a defined start zone and finish zone. The robot must reach the finish zone in autonomous mode within 5 minutes. The narrow gap (optional, extra credit) tests whether the robot can fit through a 30 cm opening without triggering a false avoidance.
Obstacle objects. For the three obstacles, use objects that are at least 15 cm wide so the HC-SR04 can detect them reliably. Good choices: hardcover books stood upright, a full water bottle, a cereal box weighted with something inside, or a short cardboard box. Narrow objects (pen, thin dowel) sit inside the sensor's beam width and may not register until the robot is very close. Mark each obstacle's position with tape so you can reset the course exactly between runs.
Success criteria:
- Robot starts in autonomous mode from the START zone (send 'M')
- Robot reaches the FINISH zone within 5 minutes without permanent stall
- Robot makes contact with zero obstacles (touches = fail)
- Robot can be switched back to RC mode at any point via 'S' or 'M' (safety)
Pass condition: the robot reaches the FINISH zone under its own power, in autonomous mode, within 5 minutes, with zero obstacle contacts. Any contact is a fault; any timeout is a failure.
Scoring (optional, for classroom use):
| Achievement | Points |
|---|---|
| Reaches FINISH without contact | 10 |
| Under 3 minutes | +3 |
| Under 2 minutes | +5 |
| Navigates the narrow gap | +5 |
| RC override works during run | +2 |
| Serial Monitor shows clean state output | +2 |
13.2 Final sketch checklist
Before the challenge run, verify every constant and function is set to its calibrated value. Use this as a literal checklist.
// ── CALIBRATION VALUES — fill in from your Module 12 measurements ────────────
const int RTRIM = ____; // from Part A of Lab 12 (your measured value)
const int CRUISE = 180; // reduce to 140 if course is tight
const int STOP_DISTANCE_CM = 20; // increase if robot still contacts obstacles
// ── AVOIDANCE TIMING — tuned for your chassis ─────────────────────────────────
const unsigned long BACK_DURATION = ____; // from Lab 10/12 (600 is a good start)
const unsigned long TURN_DURATION = ____; // from Lab 10/12 (400 is a good start)
const int OBSTACLE_CONFIRM = 3; // increase to 5 if false positives occur
// ── SENSOR ────────────────────────────────────────────────────────────────────
// Sensor mounted: horizontal ✓ centered ✓ wires secured above chassis ✓
// Verified sensor reads correctly in Serial Monitor ✓
// ── POWER ─────────────────────────────────────────────────────────────────────
// Fresh or fully charged batteries installed ✓
// Battery voltage under load: ____V (should be > 5.0V)
// Estimated run time at CRUISE=180: ~15–20 min on fresh AA batteries
Pre-run physical checks:
| Check | Pass condition |
|---|---|
| All wheels spin freely when lifted | No binding or scraping |
| Sensor mount rigid | Does not move when tapped |
| All breadboard connections seated | No wires pulling out under chassis weight |
| Motor connector screws tight | No play in the L298N terminal block |
| Bluetooth pairing confirmed | HC-05 LED blinks slowly (paired) |
Serial Monitor shows d= values |
Sensor reading before run starts |
13.3 Challenge run procedure
Set up the course on a smooth floor (tile or hardwood). Use cardboard boxes weighted with books so they don't slide when tapped.
Place the robot in the START zone, facing toward the course interior. Power on. Wait for Serial Monitor to show sensor readings.
Connect the phone app. Verify RC control works: send 'F' briefly, send 'S'. Robot should respond.
Start your timer. Send 'M'. Serial Monitor should show
MODE→AUTONOMOUSandSTATE→FORWARD.Do not touch the robot. Watch and time. Note every obstacle contact, every state transition, every place it slows or stalls.
If the robot makes contact with an obstacle: stop the timer, record the fault, and enter RC mode with 'S'. To reset: press the Arduino's reset button, reposition the robot at START facing the course interior, and restart from step 4. This is a debugging data point, not a failure to hide.
If the robot reaches the FINISH zone: stop the timer. Record the time. Run it again. A robot that finishes once needs to finish twice to be considered reliable.
After a failed run, use the Serial Monitor log to identify where it went wrong:
- What was
lastDistat the moment of contact? - Which state was active?
- How many OBSTACLE_CONFIRM counts accumulated before the state transition?
This is the debugging loop from Module 12 applied to a real performance test.
13.4 Improving for a second run
Three high-impact improvements that take under 10 minutes each:
1. Adaptive CRUISE speed
Slow down in the final 40 cm before stop. This reduces coasting distance and stops the robot more precisely.
// Adaptive speed in FORWARD state — slow down near obstacles
case FORWARD: {
int speed = (lastDist < 40) ? 120 : CRUISE;
driveForward(speed);
if (lastDist < STOP_DISTANCE_CM) {
if (++obstacleCount >= OBSTACLE_CONFIRM) {
obstacleCount = 0;
enterState(BACKING, now);
}
} else { obstacleCount = 0; }
break;
}
2. Alternating turn direction (deterministic)
Instead of random turns (which may turn back into an obstacle), alternate left/right on each avoidance:
bool lastTurnRight = true; // global
// In enterState(TURNING):
turnRight = !lastTurnRight;
lastTurnRight = turnRight;
Alternating guarantees the robot doesn't circle the same obstacle indefinitely.
3. Print avoidance count to Serial
Track how many avoidances have occurred. If avoidanceCount spikes in a specific part of the run, the course layout is challenging the robot in a predictable spot, which is a tuning opportunity.
int avoidanceCount = 0; // global
// In enterState(BACKING):
avoidanceCount++;
Serial.print("AVOIDANCE #"); Serial.println(avoidanceCount);
13.5 Documenting your robot
A completed robot is only half the deliverable. The documentation is how you prove you understand what you built, and how you'd hand it off to someone else to use or improve.
Required documentation (one page, written or typed):
Bill of materials: list every component with quantity and where it connects. Use the BOM format from Module 01.
Calibration table: record
RTRIM,STOP_DISTANCE_CM,BACK_DURATION,TURN_DURATION, and the battery voltage under load. Include the date and test surface.Known limitations: an honest list of what the robot cannot reliably do. Example: "Misses chair legs narrower than 3 cm at distances beyond 60 cm. Struggles in corners with two walls less than 40 cm apart."
Three things you would change: what would you do differently if you rebuilt it from scratch? This is not a failure list. It's engineering reflection.
Instructor note: The "three things you would change" question is the most valuable item in the documentation. Students who can articulate this clearly understand the system deeply. Students who struggle to answer it usually haven't spent enough time running and observing the robot in edge cases. Make it a required discussion item, not just a written answer.
13.6 Full final sketch
The final sketch is the unified sketch from Module 11 with Module 12's calibration applied and the Module 13 improvements added. Fill in your measured values where noted.
#include <SoftwareSerial.h>
// ── Hardware ──────────────────────────────────────────────────────────────────
const int ENA = 5, ENB = 6;
const int IN1 = 7, IN2 = 8, IN3 = 9, IN4 = 10;
const int TRIG_PIN = 11, ECHO_PIN = 12;
SoftwareSerial btSerial(2, 3);
// ── Calibration (fill in your values from Lab 12) ────────────────────────────
const int RTRIM = 0; // ← your RTRIM here
const int CRUISE = 180;
const int STOP_DISTANCE_CM = 20;
const int SLOW_DISTANCE_CM = 40; // slow to 120 inside this range
const int SLOW_SPEED = 120;
const int OBSTACLE_CONFIRM = 3;
const unsigned long SENSOR_INTERVAL = 50;
const unsigned long COMMAND_TIMEOUT = 500;
const unsigned long BACK_DURATION = 600; // ← your value here
const unsigned long TURN_DURATION = 400; // ← your value here
const unsigned long FORWARD_COOLDOWN = 300; // ms before sensor re-arms after avoidance
// ── State ─────────────────────────────────────────────────────────────────────
enum Mode { RC, AUTONOMOUS };
enum RobotState { FORWARD, BACKING, TURNING, STOPPED };
Mode currentMode = RC;
RobotState currentState = STOPPED;
unsigned long stateStartTime = 0;
unsigned long lastSensorTime = 0;
unsigned long lastCommandTime = 0;
long lastDist = 400;
int obstacleCount = 0;
bool lastTurnRight = true;
bool turnRight = true;
int avoidanceCount = 0;
// ── Motors ────────────────────────────────────────────────────────────────────
void stopMotors() { analogWrite(ENA,0); analogWrite(ENB,0); }
void setFwd() { digitalWrite(IN1,HIGH);digitalWrite(IN2,LOW);digitalWrite(IN3,HIGH);digitalWrite(IN4,LOW); }
void setBwd() { digitalWrite(IN1,LOW);digitalWrite(IN2,HIGH);digitalWrite(IN3,LOW);digitalWrite(IN4,HIGH); }
void driveForward(int s) { setFwd(); analogWrite(ENA,s); analogWrite(ENB,s-RTRIM); }
void driveBackward(int s) { setBwd(); analogWrite(ENA,s); analogWrite(ENB,s-RTRIM); }
void pivotRight(int s) { digitalWrite(IN1,HIGH);digitalWrite(IN2,LOW);digitalWrite(IN3,LOW);digitalWrite(IN4,HIGH);analogWrite(ENA,s);analogWrite(ENB,s); }
void pivotLeft(int s) { digitalWrite(IN1,LOW);digitalWrite(IN2,HIGH);digitalWrite(IN3,HIGH);digitalWrite(IN4,LOW);analogWrite(ENA,s);analogWrite(ENB,s); }
// ── Sensor ────────────────────────────────────────────────────────────────────
long readDistance() {
digitalWrite(TRIG_PIN,LOW); delayMicroseconds(2);
digitalWrite(TRIG_PIN,HIGH); delayMicroseconds(10);
digitalWrite(TRIG_PIN,LOW);
long dur = pulseIn(ECHO_PIN, HIGH, 30000);
return dur == 0 ? 400 : dur / 58;
}
// ── State transition ──────────────────────────────────────────────────────────
void enterState(RobotState s, unsigned long now) {
currentState = s;
stateStartTime = now;
switch (s) {
case FORWARD: Serial.println("STATE→FWD"); break;
case BACKING:
avoidanceCount++;
Serial.print("STATE→BACK #"); Serial.println(avoidanceCount);
stopMotors(); delay(80);
break;
case TURNING:
turnRight = !lastTurnRight; lastTurnRight = turnRight;
Serial.print("STATE→TURN "); Serial.println(turnRight ? "R" : "L");
stopMotors(); delay(80);
break;
case STOPPED: Serial.println("STATE→STOP"); stopMotors(); break;
}
}
// ── Command parser ────────────────────────────────────────────────────────────
void handleCommand(char cmd) {
lastCommandTime = millis();
if (cmd == 'M') {
if (currentMode == RC) { currentMode = AUTONOMOUS; stopMotors(); enterState(FORWARD, millis()); Serial.println("MODE→AUTO"); }
else { currentMode = RC; enterState(STOPPED, millis()); Serial.println("MODE→RC"); }
return;
}
if (cmd == 'S') { stopMotors(); currentMode = RC; enterState(STOPPED, millis()); return; }
if (currentMode != RC) return;
switch (cmd) {
case 'F': if (lastDist >= STOP_DISTANCE_CM) driveForward(CRUISE); break;
case 'B': driveBackward(CRUISE); break;
case 'L': pivotLeft(CRUISE); break;
case 'R': pivotRight(CRUISE); break;
}
}
// ── State machine ─────────────────────────────────────────────────────────────
void runStateMachine(unsigned long now) {
switch (currentState) {
case FORWARD: {
int spd = (lastDist < SLOW_DISTANCE_CM) ? SLOW_SPEED : CRUISE;
driveForward(spd);
bool coolingDown = (now - stateStartTime < FORWARD_COOLDOWN);
if (!coolingDown && lastDist < STOP_DISTANCE_CM) {
if (++obstacleCount >= OBSTACLE_CONFIRM) { obstacleCount = 0; enterState(BACKING, now); }
} else if (!coolingDown) { obstacleCount = 0; }
break;
}
case BACKING:
driveBackward(CRUISE);
if (now - stateStartTime >= BACK_DURATION) enterState(TURNING, now);
break;
case TURNING:
turnRight ? pivotRight(CRUISE) : pivotLeft(CRUISE);
if (now - stateStartTime >= TURN_DURATION) enterState(FORWARD, now);
break;
case STOPPED:
stopMotors();
break;
}
}
// ── Setup & loop ──────────────────────────────────────────────────────────────
void setup() {
randomSeed(analogRead(A0));
pinMode(ENA,OUTPUT); pinMode(ENB,OUTPUT);
pinMode(IN1,OUTPUT); pinMode(IN2,OUTPUT); pinMode(IN3,OUTPUT); pinMode(IN4,OUTPUT);
stopMotors();
pinMode(TRIG_PIN,OUTPUT); pinMode(ECHO_PIN,INPUT);
Serial.begin(9600); btSerial.begin(9600);
Serial.println("Ready — F B L R S M");
enterState(STOPPED, 0);
}
void loop() {
unsigned long now = millis();
if (now - lastSensorTime >= SENSOR_INTERVAL) { lastSensorTime = now; lastDist = readDistance(); }
if (btSerial.available() > 0) handleCommand((char)btSerial.read());
if (currentMode == RC) {
if (lastCommandTime > 0 && now - lastCommandTime > COMMAND_TIMEOUT) stopMotors();
} else {
runStateMachine(now);
}
}
Lab 13: The Navigator Challenge
Run the challenge course. Document the results. Improve. Run again.
Setup (15 minutes):
- Lay out the course as described in section 13.1: 3 m × 2 m area, three obstacles, marked START and FINISH zones.
- Complete the pre-run checklist from section 13.2.
- Upload the final sketch with your calibrated values.
Run 1: baseline 4. Start the timer. Send 'M'. Record time to finish (or record the failure mode if it doesn't finish). 5. Log: avoidance count, any contacts, Serial Monitor state output, final time.
Analysis (10 minutes): 6. Using the Serial Monitor log, identify the one highest-impact improvement. Choose from section 13.4, or identify your own.
Run 2: improved 7. Implement the improvement. Upload. Run again. Log results. 8. Compare Run 1 and Run 2: did the improvement reduce time, reduce contacts, or both?
Documentation: 9. Write the one-page documentation from section 13.5.
Module milestone: course complete. Robot completes the Navigator Challenge in autonomous mode, reaching FINISH within 5 minutes without contact. RC override responds immediately via 'S'. Serial Monitor shows clean, readable state output during the run. One-page documentation produced. Ready for Module 14: Where to Go Next.
You built a robot. From scratch. You mounted the motors, wired the driver, calibrated the drivetrain, added a sensor, replaced delay() with millis(), built a state machine, wired up Bluetooth, unified it all into a single system, debugged it, and ran it through a timed obstacle course. That is fourteen modules of mechanical, electrical, software, and systems work, and it all runs on a single chip the size of a thumbnail.
Take a moment. Look at what's on your bench. Then run it again.
Share your result. Film the Navigator Challenge run and note your time. Under 3 minutes is strong. Under 2 minutes is elite. Post the video tagged #MakeItRobot. We'd love to see your robot reach the finish line. Include your time in the caption if you're proud of it.
Self-Check: Module 13
- I completed the pre-run checklist and confirmed all calibration values are filled in before the first run.
- I ran the Navigator Challenge at least once in autonomous mode and logged avoidance count, contacts, and time.
- I used the Serial Monitor log from a failed or slow run to identify one specific improvement.
- I implemented at least one improvement from section 13.4 and compared Run 2 results to Run 1.
- The robot can be switched to RC mode via 'S' at any point during an autonomous run.
- I produced the one-page documentation covering BOM, calibration table, known limitations, and three things I would change.
- I can explain what
FORWARD_COOLDOWNdoes and why it prevents the stuck-in-corner failure mode. - I understand why alternating turn direction is more reliable than random turn direction for repeated obstacle encounters.
Key Terms Glossary
| Term | Definition |
|---|---|
| Navigator Challenge | The course completion task defined in this module: navigate a 3 m × 2 m area with three obstacles from START to FINISH in autonomous mode within 5 minutes without contact. |
| adaptive speed | Reducing drive speed as the robot approaches an obstacle so the coasting distance is shorter and stopping position is more consistent. |
| alternating turn direction | Switching between left and right turns on successive avoidances to prevent the robot from circling the same obstacle repeatedly. |
| avoidance count | A running total of how many obstacle avoidances have occurred during a run. Useful for identifying sections of the course that are consistently difficult. |
| FORWARD_COOLDOWN | A brief period after entering the FORWARD state during which the obstacle check is suppressed, preventing immediate re-detection of the same obstacle after a turn. |
| pre-run checklist | A physical and software verification performed before each challenge run to confirm wiring, calibration values, sensor readings, and battery voltage are all within acceptable ranges. |
| bill of materials (BOM) | A list of every component in the robot with quantity and connection information. Serves as the reference for rebuilding or troubleshooting the hardware. |
| engineering reflection | The practice of identifying what you would do differently if you rebuilt a system from scratch. It demonstrates deep understanding of the system's trade-offs. |
| SLOW_DISTANCE_CM | The distance threshold below which the robot drops from CRUISE speed to SLOW_SPEED, reducing coasting distance near obstacles. |
Previous: ← Module 12: Calibration, Tuning & Debugging · Next: Module 14: Where to Go Next →