Module 11: Unified RC + Autonomous Control

Level: 🟢 Beginner Board: Arduino Uno + HC-SR04 + HC-05 Prerequisites: Module 10 Estimated time: 60–90 minutes Goal: Combine RC and autonomous modes in a single sketch so the robot switches between human and self-directed control.


What You'll Learn

By the end of this module you'll understand how to architect a mode-switching system where a single command toggles between RC and autonomous behavior. You'll see how shared state variables let independent functions (sensor, Bluetooth parser, state machine) cooperate without calling each other directly, and you'll run a timed autonomous obstacle course as the Phase 3 milestone.


Every component is wired. Every behavior is working. This module combines them into one unified sketch: a robot you can switch between full RC control and fully autonomous obstacle avoidance with a single phone command. This is the Phase 3 milestone and the capstone of the entire build.


11.1 What you're combining

Across the previous ten modules you built six distinct capabilities:

Module Capability Key code
04 Motor control driveForward(), stopMotors()
05 Straight-line calibration RTRIM constant
06 Speed ramping rampUp(), rampDown()
07 Bluetooth RC handleCommand(), btSerial, dead-man timer
08–09 Distance sensing, non-blocking readDistance(), millis() timers
10 Autonomous avoidance state machine, enterState()

Each was built and tested in isolation. The challenge now is making them coexist in one sketch without any system interfering with another. The architecture that makes this possible: mode switching.

11.2 Mode switching design

The robot operates in one of two modes at any time:

enum Mode { RC, AUTONOMOUS };
Mode currentMode = RC;  // start in RC — operator has full control

In RC mode: Bluetooth commands control everything. The sensor still reads continuously, but it only triggers a safety stop and cannot initiate avoidance manoeuvres. Motor ramps are disabled for immediate response.

In AUTONOMOUS mode: the state machine from Module 10 runs. Phone commands are ignored, except for one: 'M' toggles back to RC mode.

<svg viewBox="0 0 760 240" width="100%" xmlns="http://www.w3.org/2000/svg">
  <defs>
    <marker id="aM11" 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="aG11" 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="aP11" 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="#7030d0" stroke-width="1.5" stroke-linecap="round"/></marker>
  </defs>

  <!-- RC MODE box -->
  <rect x="60" y="60" width="260" height="130" rx="6" fill="#daeaf5" stroke="#1f4d8c" stroke-width="2"/>
  <rect x="60" y="60" width="260" height="24" rx="6" fill="#1f4d8c"/>
  <text x="190" y="77" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#f5f2eb">RC MODE</text>
  <text x="76" y="104" font-family="Manrope,sans-serif" font-size="10" fill="#1f4d8c">· Phone controls all motion</text>
  <text x="76" y="120" font-family="Manrope,sans-serif" font-size="10" fill="#1f4d8c">· Sensor = safety stop only</text>
  <text x="76" y="136" font-family="Manrope,sans-serif" font-size="10" fill="#1f4d8c">· No ramps — immediate response</text>
  <text x="76" y="152" font-family="Manrope,sans-serif" font-size="10" fill="#1f4d8c">· Dead-man timer active</text>
  <text x="76" y="172" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">'M' → switch to AUTONOMOUS</text>

  <!-- AUTONOMOUS MODE box -->
  <rect x="440" y="60" width="260" height="130" rx="6" fill="#d8f0e5" stroke="#1a6b4a" stroke-width="2"/>
  <rect x="440" y="60" width="260" height="24" rx="6" fill="#1a6b4a"/>
  <text x="570" y="77" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#f5f2eb">AUTONOMOUS MODE</text>
  <text x="456" y="104" font-family="Manrope,sans-serif" font-size="10" fill="#1a6b4a">· State machine controls motion</text>
  <text x="456" y="120" font-family="Manrope,sans-serif" font-size="10" fill="#1a6b4a">· RC commands ignored</text>
  <text x="456" y="136" font-family="Manrope,sans-serif" font-size="10" fill="#1a6b4a">· Ramps enabled for smooth move</text>
  <text x="456" y="152" font-family="Manrope,sans-serif" font-size="10" fill="#1a6b4a">· Sensor drives avoidance</text>
  <text x="456" y="172" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">'M' → switch to RC</text>

  <!-- Arrows between modes -->
  <path d="M322 100 C380 100 380 100 438 100" fill="none" stroke="#7030d0" stroke-width="2" marker-end="url(#aP11)"/>
  <rect x="340" y="84" width="80" height="18" rx="3" fill="#f0e8ff"/>
  <text x="380" y="97" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#7030d0">'M' command</text>

  <path d="M438 140 C380 140 380 140 322 140" fill="none" stroke="#7030d0" stroke-width="2" marker-end="url(#aP11)"/>
  <rect x="340" y="143" width="80" height="18" rx="3" fill="#f0e8ff"/>
  <text x="380" y="156" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#7030d0">'M' command</text>

  <!-- Shared: sensor always reads -->
  <rect x="200" y="210" width="360" height="26" rx="4" fill="#1a1a18"/>
  <text x="380" y="227" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">Sensor reads at 20 Hz in both modes — only its role changes</text>
</svg>

Fig 11.1: Mode architecture. 'M' from the phone toggles between RC and AUTONOMOUS. The sensor runs continuously in both modes: in RC it only safety-stops; in AUTONOMOUS it drives the full avoidance state machine.

11.3 Updating handleCommand() for mode switching

The command parser from Module 07 needs two changes: a new 'M' case that switches modes, and a guard that ignores movement commands when in AUTONOMOUS mode.

void handleCommand(char cmd) {
  lastCommandTime = millis();

  // Mode toggle: works in any mode
  if (cmd == 'M') {
    if (currentMode == RC) {
      currentMode = AUTONOMOUS;
      stopMotors();
      enterState(FORWARD, millis());
      Serial.println("MODE: AUTONOMOUS");
    } else {
      currentMode = RC;
      stopMotors();
      enterState(STOPPED, millis());  // safe state when returning to RC
      Serial.println("MODE: RC");
    }
    return;
  }

  // Stop works in both modes
  if (cmd == 'S') {
    stopMotors();
    if (currentMode == AUTONOMOUS) {
      currentMode = RC;
      Serial.println("MODE: RC (emergency stop)");
    }
    return;
  }

  // All other commands: RC mode only
  if (currentMode != RC) return;

  switch (cmd) {
    case 'F':
      if (lastDist >= STOP_DISTANCE_CM) {   // sensor safety check in RC mode
        setDirectionForward();
        analogWrite(ENA, CRUISE);
        analogWrite(ENB, CRUISE - RTRIM);
      }
      break;
    case 'B':
      setDirectionBackward();
      analogWrite(ENA, CRUISE);
      analogWrite(ENB, CRUISE - RTRIM);
      break;
    case 'L': pivotLeft(CRUISE);  break;
    case 'R': pivotRight(CRUISE); break;
    default:  break;
  }
}

'S' as an emergency stop: Sending 'S' from the phone always stops the robot and returns to RC mode, regardless of which mode it was in. This is the fastest way to regain control if the autonomous behavior gets the robot into trouble. Assign this to a clearly visible button in your phone app.

11.4 The unified loop()

With mode switching handled in handleCommand(), the loop() becomes a clean three-section dispatcher:

void loop() {
  unsigned long now = millis();

  // ── 1. Sensor read (20 Hz, both modes) ────────────────────────────────────
  if (now - lastSensorTime >= SENSOR_INTERVAL) {
    lastSensorTime = now;
    lastDist = readDistance();
  }

  // ── 2. Bluetooth (every iteration, both modes) ────────────────────────────
  if (btSerial.available() > 0) {
    char cmd = (char) btSerial.read();
    handleCommand(cmd);
  }

  // ── 3. Behavior (mode-dependent) ──────────────────────────────────────────
  if (currentMode == RC) {
    // RC mode: just maintain dead-man timer
    if (lastCommandTime > 0 && now - lastCommandTime > COMMAND_TIMEOUT) {
      stopMotors();
    }
  } else {
    // AUTONOMOUS mode: run state machine
    runStateMachine(now);
  }
}

The sensor and Bluetooth sections always run. The third section branches on mode. runStateMachine() is the state machine body extracted from Module 10:

void runStateMachine(unsigned long now) {
  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;
  }
}

11.5 Complete unified sketch

#include <SoftwareSerial.h>

// ── Hardware pins ─────────────────────────────────────────────────────────────
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);  // HC-05: RX=D2, TX=D3

// ── 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;

const unsigned long SENSOR_INTERVAL  = 50;
const unsigned long COMMAND_TIMEOUT  = 500;
const unsigned long BACK_DURATION    = 600;
const unsigned long TURN_DURATION    = 400;

// ── State & mode ──────────────────────────────────────────────────────────────
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          turnRight       = true;

// ── Motor helpers ─────────────────────────────────────────────────────────────
void stopMotors()              { analogWrite(ENA,0); analogWrite(ENB,0); }
void setDirectionForward()     { digitalWrite(IN1,HIGH);digitalWrite(IN2,LOW);digitalWrite(IN3,HIGH);digitalWrite(IN4,LOW); }
void setDirectionBackward()    { digitalWrite(IN1,LOW);digitalWrite(IN2,HIGH);digitalWrite(IN3,LOW);digitalWrite(IN4,HIGH); }
void driveForward(int s)       { setDirectionForward();  analogWrite(ENA,s); analogWrite(ENB,s-RTRIM); }
void driveBackward(int s)      { setDirectionBackward(); 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);
      Serial.print("STATE→TURNING "); Serial.println(turnRight ? "R" : "L");
      stopMotors(); delay(80);
      break;
    case STOPPED:  Serial.println("STATE→STOPPED");  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→AUTONOMOUS");
    } else {
      currentMode = RC;
      enterState(STOPPED, millis());
      Serial.println("MODE→RC");
    }
    return;
  }

  if (cmd == 'S') {
    stopMotors();
    currentMode = RC;
    enterState(STOPPED, millis());
    Serial.println("MODE→RC (stop)");
    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;
    default:  break;
  }
}

// ── Autonomous state machine ──────────────────────────────────────────────────
void runStateMachine(unsigned long now) {
  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;
  }
}

// ── Setup ─────────────────────────────────────────────────────────────────────
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. Commands: F B L R S M(mode toggle)");
  enterState(STOPPED, 0);
}

// ── Main loop ─────────────────────────────────────────────────────────────────
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);
  }
}

11.6 Phone app configuration

Add the 'M' command to your phone app. In Serial Bluetooth Terminal or Arduino Bluetooth Controller, add a button that sends M (no newline). Label it "AUTO" on one side and "RC" on the other. It toggles.

<svg viewBox="0 0 760 220" width="100%" xmlns="http://www.w3.org/2000/svg">

  <!-- Phone outline -->
  <rect x="240" y="20" width="280" height="180" rx="12" fill="#111" stroke="#444" stroke-width="1.5"/>
  <rect x="252" y="32" width="256" height="136" rx="4" fill="#1a1a18"/>

  <!-- D-pad buttons -->
  <!-- Forward -->
  <rect x="336" y="44" width="88" height="32" rx="4" fill="#1a6b4a" stroke="#0e4030" stroke-width="1"/>
  <text x="380" y="65" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="13" fill="#a8e8c8">F</text>
  <!-- Left -->
  <rect x="262" y="78" width="72" height="32" rx="4" fill="#1f4d8c" stroke="#0e3060" stroke-width="1"/>
  <text x="298" y="99" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="13" fill="#a0c0f0">L</text>
  <!-- Stop -->
  <rect x="336" y="78" width="88" height="32" rx="4" fill="#3d3c38" stroke="#c4bfb0" stroke-width="1"/>
  <text x="380" y="99" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="13" fill="#edeae0">S</text>
  <!-- Right -->
  <rect x="426" y="78" width="72" height="32" rx="4" fill="#1f4d8c" stroke="#0e3060" stroke-width="1"/>
  <text x="462" y="99" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="13" fill="#a0c0f0">R</text>
  <!-- Back -->
  <rect x="336" y="112" width="88" height="32" rx="4" fill="#c8420a" stroke="#7a2000" stroke-width="1"/>
  <text x="380" y="133" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="13" fill="#ffc0a0">B</text>

  <!-- Mode button — prominent -->
  <rect x="262" y="112" width="72" height="32" rx="4" fill="#7030d0" stroke="#4010a0" stroke-width="1.5"/>
  <text x="298" y="133" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" fill="#e0c8ff">AUTO</text>
  <rect x="426" y="112" width="72" height="32" rx="4" fill="#7030d0" stroke="#4010a0" stroke-width="1.5"/>
  <text x="462" y="133" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" fill="#e0c8ff">AUTO</text>

  <!-- Labels -->
  <text x="298" y="156" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">sends 'M'</text>
  <text x="462" y="156" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">sends 'M'</text>
  <text x="380" y="156" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">sends 'S'</text>

  <!-- Side annotation -->
  <rect x="30" y="40" width="190" height="140" rx="4" fill="#1a1a18"/>
  <text x="125" y="60" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#888">Commands</text>
  <line x1="40" y1="68" x2="210" y2="68" stroke="#333" stroke-width="1"/>
  <text x="44" y="84" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">F</text>
  <text x="62" y="84" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">forward</text>
  <text x="44" y="100" font-family="IBM Plex Mono,monospace" font-size="10" fill="#c8420a">B</text>
  <text x="62" y="100" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">backward</text>
  <text x="44" y="116" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">L</text>
  <text x="62" y="116" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">pivot left</text>
  <text x="44" y="132" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">R</text>
  <text x="62" y="132" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">pivot right</text>
  <text x="44" y="148" font-family="IBM Plex Mono,monospace" font-size="10" fill="#edeae0">S</text>
  <text x="62" y="148" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">stop / RC mode</text>
  <text x="44" y="164" font-family="IBM Plex Mono,monospace" font-size="10" fill="#9050f0">M</text>
  <text x="62" y="164" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">toggle mode</text>
</svg>

Fig 11.2: Suggested phone app layout. F/B/L/R/S for RC control. Two AUTO buttons (left and right of the D-pad, easy to reach with either thumb) both send 'M'. Pressing S always brings the robot back to RC mode and stops it immediately. Keep it visible and accessible.

Bluetooth app tip: In Serial Bluetooth Terminal, long-press a button to edit it. Set the "send" string to exactly M with no newline, no space. The robot reads one byte at a time. A trailing newline is a second byte that gets passed to handleCommand() as an unknown command and is silently ignored, but it wastes a loop iteration and can slightly delay the mode switch response.

11.7 What the unified system teaches

The unified sketch looks more complex than any previous module but its structure is simpler than the sum of its parts. Three things run in loop(): sensor, Bluetooth, and behavior. Everything else is a function. Each function has one job.

<svg viewBox="0 0 760 260" width="100%" xmlns="http://www.w3.org/2000/svg">

  <text x="380" y="24" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#3d3c38">SYSTEM ARCHITECTURE</text>

  <!-- loop() box -->
  <rect x="300" y="40" width="160" height="60" rx="4" fill="#1a1a18" stroke="#c4bfb0" stroke-width="1.5"/>
  <text x="380" y="65" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="12" fill="#c8c4bc">loop()</text>
  <text x="380" y="82" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#888">sense · hear · behave</text>

  <!-- Three columns below -->
  <!-- Sensor column -->
  <line x1="340" y1="100" x2="160" y2="130" stroke="#1f4d8c" stroke-width="1.5"/>
  <rect x="60" y="130" width="200" height="50" rx="4" fill="#daeaf5" stroke="#1f4d8c" stroke-width="1"/>
  <text x="160" y="151" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1f4d8c">readDistance()</text>
  <text x="160" y="167" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#2c4a6e">updates lastDist — always</text>

  <!-- Bluetooth column -->
  <line x1="380" y1="100" x2="380" y2="130" stroke="#7030d0" stroke-width="1.5"/>
  <rect x="280" y="130" width="200" height="50" rx="4" fill="#f0e8ff" stroke="#7030d0" stroke-width="1"/>
  <text x="380" y="151" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#7030d0">handleCommand()</text>
  <text x="380" y="167" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#5010a0">mode toggle, RC cmds</text>

  <!-- State machine column -->
  <line x1="420" y1="100" x2="600" y2="130" stroke="#1a6b4a" stroke-width="1.5"/>
  <rect x="500" y="130" width="200" height="50" rx="4" fill="#d8f0e5" stroke="#1a6b4a" stroke-width="1"/>
  <text x="600" y="151" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#1a6b4a">runStateMachine()</text>
  <text x="600" y="167" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#0e3d28">only in AUTONOMOUS mode</text>

  <!-- Motor functions row -->
  <line x1="160" y1="180" x2="380" y2="210" stroke="#c4bfb0" stroke-width="1"/>
  <line x1="380" y1="180" x2="380" y2="210" stroke="#c4bfb0" stroke-width="1"/>
  <line x1="600" y1="180" x2="380" y2="210" stroke="#c4bfb0" stroke-width="1"/>
  <rect x="240" y="210" width="280" height="40" rx="4" fill="#edeae0" stroke="#c4bfb0" stroke-width="1.5"/>
  <text x="380" y="228" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#3d3c38">driveForward · driveBackward · pivot · stop</text>
  <text x="380" y="244" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">called by both handleCommand() and runStateMachine()</text>
</svg>

Fig 11.3: The full system architecture. loop() has three responsibilities: sense, hear, behave. Each delegates to a dedicated function. Motor primitives sit at the bottom, shared between RC and autonomous control. No function knows about the others directly: they all communicate through shared state (lastDist, currentMode, currentState).

The shared state variables (lastDist, currentMode, currentState) are the glue. handleCommand() doesn't call runStateMachine(); it just sets currentMode. runStateMachine() doesn't read Bluetooth; it just reads lastDist. Each function is independently testable because its inputs are clear.

This pattern of isolated functions communicating through shared state, coordinated by a single dispatcher loop, is the foundation of most embedded software. It scales from a classroom robot to an industrial controller.

Advanced path: command queuing. The current parser reads one byte per loop iteration. If the phone sends two bytes fast (e.g., 'F' and 'M' in rapid succession), the second byte sits in the serial buffer and is processed one loop iteration later (roughly 50 µs). For this robot this is imperceptible. For a robot that needs to process multi-byte command strings (e.g., speed values like "F180"), you'd build a small receive buffer and process it only when a full command has arrived. A simple approach: accumulate bytes until a newline '\n', then parse the full string. This is not needed here, but the pattern is worth knowing.

Self-Check: Module 11


Key Terms Glossary

Term Definition
mode switching A design pattern where a system transitions between fundamentally different operating behaviors (e.g., RC vs. autonomous) based on a command or event. The active mode determines which subsystems are active and which are passive.
shared state Global variables that multiple functions read and write. In this sketch: lastDist, currentMode, currentState. Functions communicate through shared state rather than direct calls, which keeps them loosely coupled.
priority hierarchy The ordering of which behavior takes precedence when multiple conditions are active simultaneously. In this sketch: safety stop > mode commands > RC movement > dead-man timer.
dispatcher A top-level function (here, loop()) that calls other functions based on current state, without containing logic itself. Good dispatchers are short: their job is routing, not deciding.
dead-man timer A watchdog that stops the robot if no RC command arrives within a timeout. Prevents runaway if Bluetooth drops. Only active in RC mode; the state machine handles stopping in autonomous mode.
loosely coupled Two code components are loosely coupled if they communicate only through well-defined interfaces (here, shared variables), not through direct function calls. Loosely coupled code is easier to test and modify independently.

Lab 11: The combined demonstration

This lab is the Phase 3 milestone. You'll demonstrate both modes in sequence, then run a timed autonomous obstacle course.

What you need: Complete robot with all components · phone with Bluetooth app · obstacle course (4–6 objects in a 2 m × 2 m area)

Part A: RC control verification

  1. Upload the unified sketch. Power on the robot. Open Serial Monitor. You should see "Ready. Commands: F B L R S M(mode toggle)".

  2. Connect the phone app and pair. Send 'F' and the robot drives forward. Send 'S' and the robot stops. Test all five RC commands (F, B, L, R, S). Verify each command appears in Serial Monitor.

  3. Test the safety stop in RC mode: drive the robot toward a wall with 'F'. The robot should refuse to move forward once lastDist < STOP_DISTANCE_CM. Send 'B' and it should drive backward. The sensor guards the robot from its own operator.

  4. Test the dead-man timer: send 'F', then close the Bluetooth app (or move out of range). The robot should stop within 500 ms. Reopen the app, reconnect, and send 'F' again. Normal control should resume.

Part B: Autonomous mode

  1. With the robot in an open space, send 'M'. Serial Monitor should show "MODE→AUTONOMOUS" and "STATE→FORWARD". The robot starts driving.

  2. Place a flat object in its path. Observe: does it stop, back up, turn, and resume? Serial Monitor should show the full state sequence: STATE→BACKING, STATE→TURNING, STATE→FORWARD.

  3. Send 'M' again. The robot stops and returns to RC. Send 'F' and RC control resumes immediately.

  4. Send 'F' to drive toward a wall, then send 'M' mid-drive. The robot should enter AUTONOMOUS mode immediately, where the state machine takes over and handles the wall with its avoidance sequence.

Part C: Timed autonomous run

  1. Set up the obstacle course: 4–6 objects of varying shapes at random positions in the 2 m × 2 m area.

  2. Place the robot in the center. Send 'M' to start autonomous mode. Start a timer.

  3. The robot must navigate for at least 3 minutes without getting permanently stuck. "Permanently stuck" means the robot repeats the same avoidance cycle on the same obstacle more than 5 times without clearing it.

  4. If the robot gets stuck, note: which obstacle, at what approach angle, and what the Serial Monitor showed during the stuck loop. Adjust TURN_DURATION (increase to escape corners) or BACK_DURATION (increase to clear large obstacles) and repeat.

Module milestone (Phase 3 complete): The robot navigates 3 minutes autonomously without permanent stalls, AND responds to all 6 phone commands (F, B, L, R, S, M) in RC mode, AND the sensor prevents forward movement when an obstacle is within STOP_DISTANCE_CM in RC mode. Both modes work, both transitions work, the sensor works in both contexts. All components integrated. Ready for Module 12.


Previous: ← Module 10: Obstacle Avoidance with State Machines · Next: Module 12: Calibration, Tuning & Debugging →

Related Blog Posts