Module 10: Obstacle Avoidance with State Machines
Level: 🟢 Beginner Board: Arduino Uno + HC-SR04 Prerequisites: Module 09 Estimated time: 60–90 minutes Goal: Implement a state machine that makes the robot navigate autonomously around obstacles without human input.
What You'll Learn
By the end of this module you'll understand why flat if/else logic breaks down for multi-step behaviors and how a state machine solves the problem. You'll implement a four-state obstacle avoidance loop using millis() timers, tune the timing constants against real obstacles, and add consecutive-sample filtering to ignore sensor glitches.
The robot stops before walls. Now it needs to deal with them: turn away, find a clear path, and keep moving. This module replaces the simple if/else from Module 08 with a state machine, a code structure that tracks what the robot is currently doing and transitions between behaviors cleanly. State machines are the standard architecture for autonomous robots at every scale, from hobbyist kits to Mars rovers.
10.1 Why the if/else approach breaks down
The Module 08 obstacle-stop sketch makes one binary decision every loop: obstacle close → stop, otherwise → drive. That works for stopping, but the moment you want the robot to do something after stopping (turn, reverse, scan for a clear path) a flat if/else falls apart.
// Module 08 approach: fine for stopping, broken for avoidance
void loop() {
if (dist < STOP_DISTANCE_CM) {
stopMotors();
// Now what? The robot stops here forever.
// Adding "turn right" here means it always turns right immediately.
// If you want it to back up FIRST then turn, you need delay() — back to blocking.
// If you want it to scan before turning, you need to track which direction it scanned.
// Every new behavior requires more nesting. This doesn't scale.
} else {
driveForward(CRUISE);
}
}
The problem is that the code has no memory. It doesn't know whether the robot was just driving forward, just reversing, or mid-turn. Every loop iteration starts from scratch.
A state machine solves this by giving the robot an explicit current state variable. The code asks "what state am I in?" and runs the logic for that state. Transitions between states happen on defined events. Past behavior is encoded in the current state, not in a chain of nested conditions.
10.2 State machine design
The obstacle avoidance robot needs four states:
| State | What the robot is doing | Transition out |
|---|---|---|
FORWARD |
Driving forward, scanning for obstacles | Obstacle detected → enter BACKING |
BACKING |
Reversing for a fixed time to clear the obstacle | Timer expires → enter TURNING |
TURNING |
Pivoting to face a new direction | Timer expires → enter FORWARD |
STOPPED |
Fully stopped, awaiting a deliberate restart | Never in autonomous mode (used for RC or safety) |
<svg viewBox="0 0 760 320" width="100%" xmlns="http://www.w3.org/2000/svg">
<defs>
<marker id="aS10" viewBox="0 0 10 10" refX="9" refY="5" markerWidth="6" markerHeight="6" orient="auto-start-reverse"><path d="M2 2L8 5L2 8" fill="none" stroke="#1a1a18" stroke-width="1.5" stroke-linecap="round"/></marker>
<marker id="aR10" viewBox="0 0 10 10" refX="9" refY="5" markerWidth="6" markerHeight="6" orient="auto-start-reverse"><path d="M2 2L8 5L2 8" fill="none" stroke="#c8420a" stroke-width="1.5" stroke-linecap="round"/></marker>
<marker id="aG10" viewBox="0 0 10 10" refX="9" refY="5" markerWidth="6" markerHeight="6" orient="auto-start-reverse"><path d="M2 2L8 5L2 8" fill="none" stroke="#1a6b4a" stroke-width="1.5" stroke-linecap="round"/></marker>
<marker id="aB10" viewBox="0 0 10 10" refX="9" refY="5" markerWidth="6" markerHeight="6" orient="auto-start-reverse"><path d="M2 2L8 5L2 8" fill="none" stroke="#1f4d8c" stroke-width="1.5" stroke-linecap="round"/></marker>
</defs>
<!-- FORWARD state -->
<rect x="300" y="30" width="160" height="60" rx="6" fill="#d8f0e5" stroke="#1a6b4a" stroke-width="2"/>
<text x="380" y="56" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="12" fill="#1a6b4a">FORWARD</text>
<text x="380" y="72" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#0e3d28">driveForward(CRUISE)</text>
<!-- BACKING state -->
<rect x="540" y="150" width="160" height="60" rx="6" fill="#fde8e8" stroke="#c8420a" stroke-width="2"/>
<text x="620" y="176" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="12" fill="#c8420a">BACKING</text>
<text x="620" y="192" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#7a2000">driveBackward() for 600ms</text>
<!-- TURNING state -->
<rect x="300" y="240" width="160" height="60" rx="6" fill="#daeaf5" stroke="#1f4d8c" stroke-width="2"/>
<text x="380" y="266" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="12" fill="#1f4d8c">TURNING</text>
<text x="380" y="282" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#0e3060">pivotRight() for 400ms</text>
<!-- STOPPED state -->
<rect x="60" y="150" width="160" height="60" rx="6" fill="#edeae0" stroke="#c4bfb0" stroke-width="1.5"/>
<text x="140" y="176" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="12" fill="#6b6a65">STOPPED</text>
<text x="140" y="192" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#888">stopMotors()</text>
<!-- FORWARD → BACKING: obstacle detected -->
<path d="M460 60 Q620 60 620 148" fill="none" stroke="#c8420a" stroke-width="1.5" marker-end="url(#aR10)"/>
<rect x="510" y="46" width="160" height="20" rx="3" fill="#fde8e8"/>
<text x="590" y="60" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#c8420a">dist < STOP_CM</text>
<!-- BACKING → TURNING: timer expires -->
<path d="M540 196 Q420 230 462 248" fill="none" stroke="#1f4d8c" stroke-width="1.5" marker-end="url(#aB10)"/>
<text x="450" y="228" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">backTimer done</text>
<!-- TURNING → FORWARD: timer expires -->
<path d="M380 240 Q380 210 380 92" fill="none" stroke="#1a6b4a" stroke-width="1.5" marker-end="url(#aG10)"/>
<text x="322" y="185" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">turnTimer done</text>
<!-- FORWARD → STOPPED: RC stop command -->
<path d="M300 60 Q140 60 140 148" fill="none" stroke="#888" stroke-width="1.5" stroke-dasharray="5 3" marker-end="url(#aS10)"/>
<text x="160" y="52" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">'S' command</text>
<text x="160" y="64" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">(or any state)</text>
<!-- Initial state marker -->
<line x1="340" y1="10" x2="340" y2="28" stroke="#1a6b4a" stroke-width="2" marker-end="url(#aG10)"/>
<circle cx="340" cy="6" r="4" fill="#1a6b4a"/>
<text x="350" y="10" font-family="Manrope,sans-serif" font-size="9" fill="#1a6b4a">initial state</text>
</svg>
Fig 10.1: Four-state obstacle avoidance machine. The robot starts in FORWARD. When the sensor detects an obstacle, it transitions to BACKING. When the back timer expires, it transitions to TURNING. When the turn timer expires, it returns to FORWARD and tries again. The STOPPED state is always reachable from any state via a stop command.
The key insight: state transitions fire exactly once, at the moment the event occurs. The motor command for a state runs on every loop iteration while in that state, but the transition logic runs the motor setup code once, then the steady-state code on every subsequent iteration until the next transition.
10.3 Implementing the state machine
Define the states as an enum. This gives you readable names instead of magic numbers, and the compiler catches typos.
enum RobotState {
FORWARD,
BACKING,
TURNING,
STOPPED
};
RobotState currentState = FORWARD; // start driving forward
Each state transition needs a timestamp so millis() timers can measure how long to stay in it:
unsigned long stateStartTime = 0; // when the current state began
unsigned long lastSensorTime = 0; // sensor polling timer (20 Hz)
long lastDist = 400; // most recent distance reading
const unsigned long SENSOR_INTERVAL = 50; // ms between distance reads
const unsigned long BACK_DURATION = 600; // ms to reverse after obstacle
const unsigned long TURN_DURATION = 400; // ms to pivot (tunes turn angle)
const int STOP_DISTANCE_CM = 20;
const int CRUISE = 180;
const int RTRIM = 0; // from Module 5 calibration
The loop() function becomes a state dispatcher that checks the current state and runs only the logic for that state:
void loop() {
unsigned long now = millis();
// ── Sensor read at 20 Hz (runs in all states) ─────────────────────────────
if (now - lastSensorTime >= SENSOR_INTERVAL) {
lastSensorTime = now;
lastDist = readDistance();
}
// ── State machine ─────────────────────────────────────────────────────────
switch (currentState) {
case FORWARD:
driveForward(CRUISE);
if (lastDist < STOP_DISTANCE_CM) {
enterState(BACKING, now);
}
break;
case BACKING:
driveBackward(CRUISE);
if (now - stateStartTime >= BACK_DURATION) {
enterState(TURNING, now);
}
break;
case TURNING:
pivotRight(CRUISE);
if (now - stateStartTime >= TURN_DURATION) {
enterState(FORWARD, now);
}
break;
case STOPPED:
stopMotors();
break;
}
}
The enterState() helper runs the one-time setup for a new state and records when it started:
void enterState(RobotState newState, unsigned long now) {
currentState = newState;
stateStartTime = now;
// One-time entry actions (optional — useful for logging or motor setup)
switch (newState) {
case FORWARD: Serial.println("→ FORWARD"); break;
case BACKING: Serial.println("→ BACKING"); stopMotors(); delay(80); break;
case TURNING: Serial.println("→ TURNING"); stopMotors(); delay(80); break;
case STOPPED: Serial.println("→ STOPPED"); stopMotors(); break;
}
}
The two
delay(80)calls insideenterState()are brief coasting pauses that let the motors decelerate slightly before reversing direction. This is the one place blocking delays are acceptable: a short, predictable pause at a state transition, not inside the steady-state loop. At 80 ms, the robot barely notices. Removing them causes the motor driver to immediately reverse a spinning motor, which can stress the driver over time.
<svg viewBox="0 0 760 240" width="100%" xmlns="http://www.w3.org/2000/svg">
<defs>
<marker id="aF10" viewBox="0 0 10 10" refX="9" refY="5" markerWidth="5" markerHeight="5" orient="auto-start-reverse"><path d="M2 2L8 5L2 8" fill="none" stroke="#1a1a18" stroke-width="1.5" stroke-linecap="round"/></marker>
</defs>
<!-- loop() call flow -->
<text x="380" y="22" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#3d3c38">loop() CALL FLOW — state machine</text>
<!-- Sensor block -->
<rect x="30" y="40" width="140" height="44" rx="4" fill="#1a1a18" stroke="#1a6b4a" stroke-width="1"/>
<text x="100" y="58" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a8e8c8">sensor timer</text>
<text x="100" y="74" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#60b080">update lastDist</text>
<!-- Arrow to switch -->
<line x1="172" y1="62" x2="208" y2="62" stroke="#1a1a18" stroke-width="1.5" marker-end="url(#aF10)"/>
<!-- Switch diamond -->
<polygon points="260,36 320,62 260,88 200,62" fill="#f5eed8" stroke="#c8aa60" stroke-width="1.5"/>
<text x="260" y="58" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#8a6800">switch</text>
<text x="260" y="72" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#8a6800">(state)</text>
<!-- FORWARD case -->
<line x1="260" y1="36" x2="260" y2="10" stroke="#1a1a18" stroke-width="1" marker-end="url(#aF10)"/>
<rect x="200" y="100" width="120" height="60" rx="4" fill="#d8f0e5" stroke="#1a6b4a" stroke-width="1.5"/>
<text x="260" y="124" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">FORWARD</text>
<text x="260" y="140" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3d28">driveForward()</text>
<text x="260" y="153" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3d28">check dist</text>
<line x1="260" y1="88" x2="260" y2="98" stroke="#1a6b4a" stroke-width="1.5" marker-end="url(#aF10)"/>
<!-- BACKING case -->
<line x1="320" y1="50" x2="420" y2="50" stroke="#1a1a18" stroke-width="1" marker-end="url(#aF10)"/>
<rect x="418" y="100" width="120" height="60" rx="4" fill="#fde8e8" stroke="#c8420a" stroke-width="1.5"/>
<text x="478" y="124" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#c8420a">BACKING</text>
<text x="478" y="140" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#7a2000">driveBackward()</text>
<text x="478" y="153" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#7a2000">check timer</text>
<line x1="478" y1="50" x2="478" y2="98" stroke="#c8420a" stroke-width="1.5" marker-end="url(#aF10)"/>
<!-- TURNING case -->
<line x1="320" y1="74" x2="610" y2="74" stroke="#1a1a18" stroke-width="1" marker-end="url(#aF10)"/>
<rect x="610" y="100" width="120" height="60" rx="4" fill="#daeaf5" stroke="#1f4d8c" stroke-width="1.5"/>
<text x="670" y="124" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">TURNING</text>
<text x="670" y="140" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3060">pivotRight()</text>
<text x="670" y="153" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3060">check timer</text>
<line x1="670" y1="74" x2="670" y2="98" stroke="#1f4d8c" stroke-width="1.5" marker-end="url(#aF10)"/>
<!-- Return / converge -->
<line x1="260" y1="162" x2="260" y2="196" stroke="#888" stroke-width="1"/>
<line x1="478" y1="162" x2="478" y2="196" stroke="#888" stroke-width="1"/>
<line x1="670" y1="162" x2="670" y2="196" stroke="#888" stroke-width="1"/>
<line x1="260" y1="196" x2="670" y2="196" stroke="#888" stroke-width="1"/>
<line x1="464" y1="196" x2="464" y2="218" stroke="#888" stroke-width="1.5" marker-end="url(#aF10)"/>
<text x="464" y="232" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#888">loop() returns — runs again immediately</text>
</svg>
Fig 10.2: Every loop() iteration: update sensor, dispatch to current state's case, return. Each case runs its steady-state motor command and checks exactly one transition condition. No nested logic, no blocking waits.
10.4 Motor functions for the new states
The Module 04 sketch had driveForward(). You need two more: driveBackward() and pivotRight().
void driveBackward(int speed) {
digitalWrite(IN1, LOW); digitalWrite(IN2, HIGH); // left motor: reverse
digitalWrite(IN3, LOW); digitalWrite(IN4, HIGH); // right motor: reverse
analogWrite(ENA, speed);
analogWrite(ENB, speed - RTRIM);
}
void pivotRight(int speed) {
// Left wheel forward, right wheel backward → pivot clockwise
digitalWrite(IN1, HIGH); digitalWrite(IN2, LOW); // left: forward
digitalWrite(IN3, LOW); digitalWrite(IN4, HIGH); // right: backward
analogWrite(ENA, speed);
analogWrite(ENB, speed); // no trim on pivot — equal speeds
}
void pivotLeft(int speed) {
// Right wheel forward, left wheel backward → pivot counter-clockwise
digitalWrite(IN1, LOW); digitalWrite(IN2, HIGH); // left: backward
digitalWrite(IN3, HIGH); digitalWrite(IN4, LOW); // right: forward
analogWrite(ENA, speed);
analogWrite(ENB, speed);
}
Which direction to turn? Always turning right means the robot circles the same obstacle endlessly if it's in a corner. Module 11 adds a smarter strategy: pick a random direction at each turn, or alternate left/right, to improve coverage. For now, always right is fine for open-space testing.
10.5 Tuning BACK_DURATION and TURN_DURATION
These two constants directly control how the robot moves around obstacles. Getting them right requires testing against actual obstacles in your environment.
<svg viewBox="0 0 760 280" width="100%" xmlns="http://www.w3.org/2000/svg">
<!-- Top-down robot path diagram -->
<text x="380" y="22" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#3d3c38">AVOIDANCE GEOMETRY — top-down view</text>
<!-- Wall obstacle -->
<rect x="290" y="50" width="200" height="20" rx="2" fill="#3d3c38"/>
<text x="390" y="64" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#edeae0">WALL</text>
<!-- Robot initial position -->
<rect x="370" y="90" width="24" height="18" rx="2" fill="#1a6b4a"/>
<polygon points="382,90 376,96 388,96" fill="#a8e8c8"/>
<text x="330" y="100" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">① FORWARD</text>
<text x="330" y="112" text-anchor="end" font-family="Manrope,sans-serif" font-size="9" fill="#888">detects wall at 20cm</text>
<!-- Arrow forward toward wall -->
<line x1="382" y1="90" x2="382" y2="73" stroke="#1a6b4a" stroke-width="1" stroke-dasharray="3 2" opacity=".5"/>
<!-- Robot backing position -->
<rect x="370" y="140" width="24" height="18" rx="2" fill="#c8420a"/>
<polygon points="382,158 376,152 388,152" fill="#ffc0a0"/>
<text x="330" y="150" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">② BACKING</text>
<text x="330" y="162" text-anchor="end" font-family="Manrope,sans-serif" font-size="9" fill="#888">600ms reverse</text>
<!-- Arrow backing -->
<line x1="382" y1="160" x2="382" y2="140" stroke="#c8420a" stroke-width="1.5"/>
<!-- Robot turning position -->
<rect x="370" y="194" width="24" height="18" rx="2" fill="#1f4d8c" transform="rotate(90 382 203)"/>
<polygon points="393,203 387,197 387,209" fill="#a0c0f0"/>
<text x="330" y="200" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1f4d8c">③ TURNING</text>
<text x="330" y="212" text-anchor="end" font-family="Manrope,sans-serif" font-size="9" fill="#888">400ms pivot right</text>
<!-- Arc for turn -->
<path d="M382 200 Q400 190 410 203" fill="none" stroke="#1f4d8c" stroke-width="1.5"/>
<!-- Robot resume forward -->
<rect x="400" y="194" width="24" height="18" rx="2" fill="#1a6b4a"/>
<polygon points="424,203 418,197 418,209" fill="#a8e8c8"/>
<text x="520" y="200" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">④ FORWARD</text>
<text x="520" y="212" font-family="Manrope,sans-serif" font-size="9" fill="#888">new direction</text>
<!-- Tuning guide box -->
<rect x="470" y="50" width="270" height="130" rx="4" fill="#1a1a18"/>
<text x="605" y="70" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#888">TUNING GUIDE</text>
<line x1="480" y1="76" x2="730" y2="76" stroke="#333" stroke-width="1"/>
<text x="484" y="92" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">BACK_DURATION:</text>
<text x="484" y="106" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">Too short: robot turns into wall</text>
<text x="484" y="120" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">400–800ms works for most kits</text>
<text x="484" y="138" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">TURN_DURATION:</text>
<text x="484" y="152" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">Too short: only slight angle change</text>
<text x="484" y="166" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">300–500ms ≈ 70–100° pivot</text>
</svg>
Fig 10.3: Avoidance geometry: the robot detects the wall (①), reverses to clear it (②), pivots right (③), then resumes forward in a new direction (④). BACK_DURATION controls how far back it travels. TURN_DURATION controls the turn angle (longer means a sharper turn).
Starting values and what to adjust:
| Constant | Start value | Too small | Too large |
|---|---|---|---|
BACK_DURATION |
600 ms | Robot pivots and immediately re-detects wall | Robot reverses too far, wastes space |
TURN_DURATION |
400 ms | Robot barely changes direction, re-encounters same wall | Robot spins more than 180°, gets confused in narrow spaces |
STOP_DISTANCE_CM |
20 cm | Robot drives into obstacles before stopping | Robot stops too far away, avoidance is overly conservative |
Increase BACK_DURATION by 100 ms if the robot keeps hitting the same wall. Increase TURN_DURATION by 100 ms if it keeps encountering the same obstacle from a slightly different angle. Test in an open area first, with at least 1 m² of clear floor.
10.6 Sensor noise and consecutive-sample filtering
The Module 08 "Advanced path" mentioned handling sensor noise in the state machine. Here's how: require the sensor reading to exceed the threshold for N consecutive passes before triggering a transition. This prevents a single bad reading from causing an avoidance manoeuvre.
// Consecutive-sample filter — catches sustained obstacles, ignores glitches
int obstacleCount = 0;
const int OBSTACLE_CONFIRM = 3; // require 3 consecutive close readings
// Inside the FORWARD case:
case FORWARD:
driveForward(CRUISE);
if (lastDist < STOP_DISTANCE_CM) {
obstacleCount++;
if (obstacleCount >= OBSTACLE_CONFIRM) {
obstacleCount = 0;
enterState(BACKING, now);
}
} else {
obstacleCount = 0; // clear on any non-close reading
}
break;
At 20 Hz, three consecutive readings take 150 ms, so the robot travels about 3 cm at typical speed. This adds a small amount of stopping distance (increase STOP_DISTANCE_CM by 5 cm to compensate). The benefit: glitches, narrow posts at the beam edge, and brief electrical noise can no longer trigger an avoidance manoeuvre.
Advanced path: randomized turn direction. A robot that always turns right will circle a convex obstacle indefinitely. Add a random turn direction at each avoidance event:
bool turnRight = random(2);before entering the TURNING state, then usepivotRight()orpivotLeft()accordingly.random(2)returns 0 or 1 with equal probability. CallrandomSeed(analogRead(A0))insetup()to seed the random number generator from floating-point noise on an unconnected analog pin. Without this, the sequence is deterministic and the robot develops predictable patterns. A0 must be left unconnected for this to work. If anything is wired to A0 from a previous experiment, disconnect it: a driven signal on A0 will produce the same seed on every power-on, making the turn sequence deterministic again.
10.7 Complete obstacle avoidance sketch
#include <SoftwareSerial.h>
// ── Pin constants ─────────────────────────────────────────────────────────────
const int ENA = 5, ENB = 6;
const int IN1 = 7, IN2 = 8, IN3 = 9, IN4 = 10;
const int TRIG_PIN = 11, ECHO_PIN = 12;
// ── Tuning constants ──────────────────────────────────────────────────────────
const int RTRIM = 0; // Module 5 calibration value
const int CRUISE = 180;
const int STOP_DISTANCE_CM = 20;
const int OBSTACLE_CONFIRM = 3; // consecutive close readings to trigger avoidance
const unsigned long SENSOR_INTERVAL = 50;
const unsigned long BACK_DURATION = 600;
const unsigned long TURN_DURATION = 400;
// ── State machine ─────────────────────────────────────────────────────────────
enum RobotState { FORWARD, BACKING, TURNING, STOPPED };
RobotState currentState = FORWARD;
unsigned long stateStartTime = 0;
unsigned long lastSensorTime = 0;
long lastDist = 400;
int obstacleCount = 0;
bool turnRight = true; // set randomly in enterState(TURNING)
// ── Motor functions ───────────────────────────────────────────────────────────
void stopMotors() { analogWrite(ENA,0); analogWrite(ENB,0); }
void driveForward(int s) { digitalWrite(IN1,HIGH);digitalWrite(IN2,LOW);digitalWrite(IN3,HIGH);digitalWrite(IN4,LOW);analogWrite(ENA,s);analogWrite(ENB,s-RTRIM); }
void driveBackward(int s) { digitalWrite(IN1,LOW);digitalWrite(IN2,HIGH);digitalWrite(IN3,LOW);digitalWrite(IN4,HIGH);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); }
// ── Distance 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: FORWARD"); break;
case BACKING: Serial.println("STATE: BACKING"); stopMotors(); delay(80); break;
case TURNING:
turnRight = random(2); // randomize direction each avoidance
Serial.print("STATE: TURNING "); Serial.println(turnRight ? "R" : "L");
stopMotors(); delay(80);
break;
case STOPPED: Serial.println("STATE: STOPPED"); stopMotors(); break;
}
}
// ── Setup ─────────────────────────────────────────────────────────────────────
void setup() {
randomSeed(analogRead(A0)); // seed RNG from floating analog pin
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);
Serial.println("Obstacle avoidance ready — place on floor and power on.");
enterState(FORWARD, 0);
}
// ── Main loop ─────────────────────────────────────────────────────────────────
void loop() {
unsigned long now = millis();
// Sensor at 20 Hz
if (now - lastSensorTime >= SENSOR_INTERVAL) {
lastSensorTime = now;
lastDist = readDistance();
Serial.print("d="); Serial.print(lastDist);
Serial.print(" state="); Serial.println(currentState);
}
switch (currentState) {
case FORWARD:
driveForward(CRUISE);
if (lastDist < STOP_DISTANCE_CM) {
if (++obstacleCount >= OBSTACLE_CONFIRM) {
obstacleCount = 0;
enterState(BACKING, now);
}
} else {
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;
}
}
Self-Check: Module 10
- I can explain why a flat if/else approach cannot implement multi-step behaviors like back-then-turn obstacle avoidance.
- I can define an
enumfor robot states and use aswitchstatement to dispatch behavior based oncurrentState. - I understand why state transitions should fire exactly once and how
enterState()enforces that. - I can use
millis()timers inside states to control how long the robot stays in BACKING and TURNING. - I know how to tune
BACK_DURATIONandTURN_DURATIONby observing the robot's physical path around an obstacle. - I can implement consecutive-sample filtering to prevent sensor glitches from triggering false avoidance manoeuvres.
- I understand why randomizing the turn direction prevents the robot from circling a convex obstacle indefinitely.
Key Terms Glossary
| Term | Definition |
|---|---|
| state machine | A programming pattern that models behavior as a set of discrete states, with defined rules for transitioning between them. The program always knows exactly which state it's in, and each state runs only its own logic. |
enum |
An Arduino/C++ keyword that defines a named set of integer constants. enum RobotState { FORWARD, BACKING, TURNING } creates three named values. The compiler maps them to 0, 1, 2 internally but your code uses the readable names. |
| state transition | A change from one state to another, triggered by a defined event (sensor threshold, timer expiry, received command). Transitions should fire exactly once, not every loop iteration. |
enterState() |
A helper function that updates currentState, records the transition time in stateStartTime, and runs one-time entry actions (like stopping the motors before reversing). |
| consecutive-sample filter | A noise-rejection technique that requires a sensor threshold to be exceeded for N consecutive readings before acting. Prevents single bad samples from triggering state changes. |
random() |
Arduino function that returns a pseudo-random integer. random(2) returns 0 or 1. Must be seeded with randomSeed(), otherwise the sequence is the same every power cycle. |
randomSeed() |
Seeds Arduino's random number generator. randomSeed(analogRead(A0)) uses electrical noise on a floating analog pin as a seed, producing a different sequence on every power-on. |
| avoidance geometry | The physical path a robot takes during an obstacle avoidance manoeuvre. Controlled by BACK_DURATION (how far it reverses) and TURN_DURATION (how many degrees it rotates). |
Hardware check before you start. Verify that your robot drives forward and stops when the sensor detects an obstacle, as it did at the end of Module 08's lab. If that baseline behavior is broken, fix it before adding the state machine. A hardware fault (loose sensor wire, motor connector not seated, dead battery) produces symptoms that look exactly like a software bug in the state machine. Eliminate hardware as the cause first.
Lab 10: Autonomous obstacle avoidance in an open room
Upload the complete avoidance sketch, set the robot loose in a clear area, and tune the timing constants until it navigates without getting stuck.
What you need: Completed robot from Module 09 · clear floor space (minimum 1.5 m × 1.5 m) · a few objects to use as obstacles (chairs, cardboard boxes, books) · tape measure or ruler
Before you start: Press every jumper wire firmly into the breadboard. This is the first module where the robot runs autonomously for extended periods, and motor vibration gradually loosens breadboard connections. A single loose wire can cause unpredictable behavior that looks like a code bug but is purely mechanical. Make this a habit before every test session.
Upload the complete sketch from section 10.7. Set
BACK_DURATION = 600,TURN_DURATION = 400,STOP_DISTANCE_CM = 20. Open Serial Monitor at 9600 baud.Before powering on: place the robot in the center of the clear space. No obstacles yet. Hands and feet clear of the drive wheels.
Power on. The robot should immediately drive forward and print "STATE: FORWARD" in Serial Monitor. Let it run until it reaches a wall. Observe: does it stop before the wall? Does it back up cleanly? Does it pivot and resume?
Watch for the most common failure modes:
- Hits the wall before stopping: increase
STOP_DISTANCE_CMby 5. - Backs up and immediately re-detects the same wall: increase
BACK_DURATIONby 100. - Pivots a tiny amount and faces the same wall: increase
TURN_DURATIONby 100. - False avoidances on open floor: the sensor is likely aimed downward. Remount it horizontally.
- Hits the wall before stopping: increase
Once the robot clears a flat wall reliably, add obstacles: place a cardboard box in the path. Does it avoid the box? Try a narrow chair leg. The ±15° beam may miss it. Note which objects the robot can and cannot detect.
Add a second object close to the first to create a narrow corridor. Can the robot find its way through? At what corridor width does it get stuck?
Serial Monitor analysis: watch the
d=andstate=output during an avoidance sequence. You should seed=values drop belowSTOP_DISTANCE_CMfor 3 consecutive readings, then "STATE: BACKING", a sequence of rising d= values as it reverses, then "STATE: TURNING", then "STATE: FORWARD".Optional: increase
OBSTACLE_CONFIRMto 5. Does the robot sometimes make contact with obstacles now? This shows the trade-off between noise rejection and response time.
Module milestone: The robot navigates an obstacle course without human input, backing and turning away from detected objects, with randomized turn direction. Serial Monitor shows clean state transitions. The robot can run for at least 3 minutes in a room with 4–6 obstacles without getting permanently stuck. Ready for Module 11.
Previous: ← Module 09: Non-blocking Timing with millis() · Next: Module 11: Unified RC + Autonomous Control →