Module 9: Non-blocking Timing with millis()

Level: 🟢 Beginner Board: Arduino Uno Prerequisites: Module 08 Estimated time: 45–60 minutes Goal: Replace delay()-based timing with millis() so the robot can read sensors and drive motors simultaneously without blocking.


What You'll Learn

By the end of this module you'll understand why delay() makes a robot unresponsive and how millis()-based timers solve the problem. You'll be able to run multiple independent timers at different rates inside a single loop(), and you'll combine sensor checking with Bluetooth RC control in one non-blocking sketch.


The obstacle-stop robot from Module 08 works, but it has a hidden structural flaw: delay(). While the Arduino sits inside a delay, it can't read sensors, respond to Bluetooth commands, or do anything else. One delay blocks the world. This module replaces every delay() in your robot with millis()-based timing, making the loop non-blocking and the robot genuinely responsive.

A note before you refactor. The delay()-based code from the previous modules was the right approach for where you were. Learning one concept at a time: drive the motors, then add a sensor, then time the readings. That is how you build a solid foundation without getting lost. The switch to millis() is not a correction of a mistake. It is the natural next step: now that the fundamentals are working, you are ready to remove the training wheels. Think of it as upgrading your code, not rewriting a failure.


9.1 The problem with delay()

delay(50) in Module 08's loop() tells the Arduino to pause for 50 milliseconds before doing anything else. During those 50 ms, the processor is alive but idle: it ignores incoming Bluetooth bytes, skips sensor readings, and can't update motor state. For a simple obstacle-stop robot this is acceptable. The moment you want the robot to do two things at once (sense distance and respond to phone commands), delay() makes it impossible.

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

  <!-- Title -->
  <text x="380" y="24" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#c8420a">delay() BLOCKS EVERYTHING</text>

  <!-- Timeline bar -->
  <line x1="40" y1="80" x2="720" y2="80" stroke="#c4bfb0" stroke-width="1.5"/>
  <text x="740" y="84" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">time →</text>

  <!-- Active work blocks -->
  <rect x="40" y="60" width="60" height="40" rx="2" fill="#1a6b4a" stroke="#0e4030" stroke-width="1"/>
  <text x="70" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a8e8c8">sense</text>

  <rect x="102" y="60" width="40" height="40" rx="2" fill="#1f4d8c" stroke="#0e3060" stroke-width="1"/>
  <text x="122" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a0c0f0">decide</text>

  <rect x="144" y="60" width="40" height="40" rx="2" fill="#8a6800" stroke="#5a4200" stroke-width="1"/>
  <text x="164" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#f5eed8">act</text>

  <!-- delay block — big red -->
  <rect x="186" y="60" width="200" height="40" rx="2" fill="#c8420a" stroke="#7a2000" stroke-width="1.5"/>
  <text x="286" y="82" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" fill="white">delay(200)</text>
  <text x="286" y="95" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#ffc0a0">200 ms — doing nothing</text>

  <!-- Next sense etc -->
  <rect x="388" y="60" width="60" height="40" rx="2" fill="#1a6b4a" stroke="#0e4030" stroke-width="1"/>
  <text x="418" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a8e8c8">sense</text>
  <rect x="450" y="60" width="40" height="40" rx="2" fill="#1f4d8c" stroke="#0e3060" stroke-width="1"/>
  <text x="470" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a0c0f0">decide</text>
  <rect x="492" y="60" width="40" height="40" rx="2" fill="#8a6800" stroke="#5a4200" stroke-width="1"/>
  <text x="512" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#f5eed8">act</text>
  <rect x="534" y="60" width="180" height="40" rx="2" fill="#c8420a" stroke="#7a2000" stroke-width="1.5"/>
  <text x="624" y="85" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" fill="white">delay(200)</text>

  <!-- Missed BT command annotation -->
  <line x1="260" y1="40" x2="260" y2="58" stroke="#7030d0" stroke-width="1.5" stroke-dasharray="3 2"/>
  <circle cx="260" cy="36" r="6" fill="#7030d0"/>
  <text x="265" y="32" font-family="Manrope,sans-serif" font-size="9" fill="#7030d0">BT command arrives</text>
  <text x="265" y="44" font-family="Manrope,sans-serif" font-size="9" fill="#7030d0">— never seen!</text>

  <!-- Missed obstacle annotation -->
  <line x1="340" y1="40" x2="340" y2="58" stroke="#c8420a" stroke-width="1.5" stroke-dasharray="3 2"/>
  <rect x="345" y="24" width="110" height="18" rx="2" fill="#fde8e8"/>
  <text x="400" y="37" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#c8420a">obstacle appeared — missed</text>

  <!-- Bottom label -->
  <rect x="40" y="116" width="680" height="30" rx="3" fill="#1a1a18"/>
  <text x="380" y="135" text-anchor="middle" font-family="Manrope,sans-serif" font-size="11" fill="#c8c4bc">Every delay() is a blindspot — sensors go unread, serial goes unheard, state goes unseen</text>
</svg>

Fig 9.1: With delay(), the loop stalls for the full duration. A Bluetooth command arriving during a delay is silently discarded. An obstacle entering the sensor beam during a delay gets no response. The robot is effectively offline while the delay runs.

The fix is to stop pausing and start checking. Instead of "wait 200 ms then continue," you ask "has 200 ms passed since last time?" If yes, do the action. If no, skip it and move on. The loop keeps running at full speed, servicing sensors, serial, and motor logic every iteration.

9.2 How millis() works

millis() returns the number of milliseconds since the Arduino was powered on or last reset, as an unsigned long. It increments in the background without your code doing anything. It never blocks.

unsigned long now = millis();  // e.g. 4823 ms after power-on

The counter rolls over after approximately 49.7 days. For a robot running for minutes or hours at a time, rollover is irrelevant. For long-running installations, always use subtraction (millis() - lastTime) rather than comparison (millis() > lastTime + interval): subtraction handles rollover automatically due to unsigned integer arithmetic.

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

  <!-- millis() counter visualization -->
  <text x="380" y="24" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#3d3c38">millis() — milliseconds since power-on</text>

  <!-- Timeline -->
  <line x1="40" y1="80" x2="720" y2="80" stroke="#c4bfb0" stroke-width="1.5"/>
  <text x="740" y="84" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">t →</text>

  <!-- Tick marks with values -->
  <line x1="40" y1="72" x2="40" y2="88" stroke="#888" stroke-width="1.5"/>
  <text x="40" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">0</text>

  <line x1="160" y1="72" x2="160" y2="88" stroke="#888" stroke-width="1"/>
  <text x="160" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">1000</text>

  <line x1="280" y1="72" x2="280" y2="88" stroke="#888" stroke-width="1"/>
  <text x="280" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">2000</text>

  <line x1="400" y1="72" x2="400" y2="88" stroke="#888" stroke-width="1"/>
  <text x="400" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">3000</text>

  <line x1="520" y1="72" x2="520" y2="88" stroke="#888" stroke-width="1"/>
  <text x="520" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">4000</text>

  <line x1="640" y1="72" x2="640" y2="88" stroke="#888" stroke-width="1"/>
  <text x="640" y="100" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">5000</text>

  <!-- lastTime marker -->
  <line x1="280" y1="50" x2="280" y2="72" stroke="#c8420a" stroke-width="2"/>
  <circle cx="280" cy="46" r="5" fill="#c8420a"/>
  <text x="280" y="40" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">lastTime</text>
  <text x="280" y="50" text-anchor="middle" font-family="Manrope,sans-serif" font-size="8" fill="#c8420a">2000</text>

  <!-- interval arrow -->
  <line x1="280" y1="60" x2="480" y2="60" stroke="#1a6b4a" stroke-width="1.5" stroke-dasharray="5 3"/>
  <line x1="480" y1="55" x2="480" y2="65" stroke="#1a6b4a" stroke-width="1.5"/>
  <text x="380" y="56" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">interval = 200 ms</text>

  <!-- now marker -->
  <line x1="480" y1="50" x2="480" y2="72" stroke="#1f4d8c" stroke-width="2"/>
  <circle cx="480" cy="46" r="5" fill="#1f4d8c"/>
  <text x="480" y="40" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1f4d8c">now</text>
  <text x="480" y="50" text-anchor="middle" font-family="Manrope,sans-serif" font-size="8" fill="#1f4d8c">2200</text>

  <!-- Code box -->
  <rect x="40" y="116" width="680" height="50" rx="4" fill="#1a1a18"/>
  <text x="55" y="135" font-family="IBM Plex Mono,monospace" font-size="10" fill="#c8b400">if (millis() - lastTime &gt;= interval) {</text>
  <text x="67" y="151" font-family="IBM Plex Mono,monospace" font-size="10" fill="#a8e8c8">  doTheAction();   lastTime = millis();</text>
  <text x="55" y="160" font-family="IBM Plex Mono,monospace" font-size="10" fill="#c8b400">}</text>
</svg>

Fig 9.2: millis() counts continuously. To fire an action every 200 ms, record when you last fired it (lastTime), then check whether the elapsed time (millis() - lastTime) has reached the interval. If yes, act and reset the timer. If no, skip and return so the loop keeps running.

The pattern in code is always the same:

unsigned long lastSensorTime = 0;
const unsigned long SENSOR_INTERVAL = 50;  // ms between readings

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

  if (now - lastSensorTime >= SENSOR_INTERVAL) {
    lastSensorTime = now;
    // do the timed action here
    long dist = readDistance();
    // ...
  }

  // everything below here runs every loop iteration, unblocked
}

Name your timer variables after what they time (lastSensorTime, lastPrintTime, lastBlinkTime), not generic names like timer1. When you have three timers, generic names become unreadable immediately.

9.3 Replacing delay() in the obstacle-stop sketch

The Module 08 obstacle-stop sketch has one delay(50) at the bottom of loop(). Removing it and replacing with a millis() check is a direct substitution.

// ── Before (Module 08) ────────────────────────────────────────────────────────
void loop() {
  long dist = readDistance();
  Serial.print("Distance: "); Serial.println(dist);
  if (dist < STOP_DISTANCE_CM) stopMotors();
  else driveForward(CRUISE);
  delay(50);  // blocks for 50 ms — nothing else can run
}

// ── After (Module 09) ─────────────────────────────────────────────────────────
unsigned long lastSensorTime = 0;
const unsigned long SENSOR_INTERVAL = 50;

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

  if (now - lastSensorTime >= SENSOR_INTERVAL) {
    lastSensorTime = now;
    long dist = readDistance();
    Serial.print("Distance: "); Serial.println(dist);
    if (dist < STOP_DISTANCE_CM) stopMotors();
    else driveForward(CRUISE);
  }
  // loop() returns immediately if interval hasn't elapsed
  // everything else — Bluetooth, extra sensors — fits in here
}

The sensor fires at exactly the same rate (20 Hz). The robot behavior is identical. The difference is that loop() now returns between sensor reads instead of blocking. Adding Bluetooth handling is now a one-liner alongside the sensor check.

9.4 Multiple independent timers

The real power of millis() becomes clear when you need several things happening at different rates. Sensors at 20 Hz. Serial prints at 5 Hz (to keep the monitor readable). A status LED blink at 1 Hz. All three running simultaneously without any of them blocking the others.

<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">THREE INDEPENDENT TIMERS — no blocking</text>

  <!-- Timeline -->
  <line x1="40" y1="130" x2="720" y2="130" stroke="#c4bfb0" stroke-width="1.5"/>

  <!-- Sensor events (50ms = 20Hz) — green dots every ~60px  -->
  <text x="20" y="62" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">sensor</text>
  <text x="20" y="72" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1a6b4a">50 ms</text>
  <g fill="#1a6b4a">
    <circle cx="60" cy="66" r="6"/>
    <circle cx="118" cy="66" r="6"/>
    <circle cx="176" cy="66" r="6"/>
    <circle cx="234" cy="66" r="6"/>
    <circle cx="292" cy="66" r="6"/>
    <circle cx="350" cy="66" r="6"/>
    <circle cx="408" cy="66" r="6"/>
    <circle cx="466" cy="66" r="6"/>
    <circle cx="524" cy="66" r="6"/>
    <circle cx="582" cy="66" r="6"/>
    <circle cx="640" cy="66" r="6"/>
    <circle cx="698" cy="66" r="6"/>
  </g>
  <line x1="60" y1="72" x2="60" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="118" y1="72" x2="118" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="176" y1="72" x2="176" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="234" y1="72" x2="234" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="292" y1="72" x2="292" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="350" y1="72" x2="350" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="408" y1="72" x2="408" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="466" y1="72" x2="466" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="524" y1="72" x2="524" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="582" y1="72" x2="582" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>
  <line x1="640" y1="72" x2="640" y2="128" stroke="#1a6b4a" stroke-width="0.5" opacity=".3"/>

  <!-- Serial print events (200ms = 5Hz) — blue squares every ~240px  -->
  <text x="20" y="110" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1f4d8c">serial</text>
  <text x="20" y="120" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#1f4d8c">200 ms</text>
  <g fill="#1f4d8c">
    <rect x="53" y="100" width="14" height="14" rx="2"/>
    <rect x="292" y="100" width="14" height="14" rx="2"/>
    <rect x="531" y="100" width="14" height="14" rx="2"/>
  </g>

  <!-- LED blink (1000ms = 1Hz) — orange diamonds every ~1200px scaled down  -->
  <text x="20" y="152" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">LED</text>
  <text x="20" y="162" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">1000 ms</text>
  <g fill="#c8420a">
    <polygon points="60,143 74,155 60,167 46,155"/>
    <polygon points="348,143 362,155 348,167 334,155"/>
    <polygon points="638,143 652,155 638,167 624,155"/>
  </g>

  <!-- loop() runs label -->
  <rect x="40" y="185" width="680" height="50" rx="4" fill="#1a1a18"/>
  <text x="380" y="204" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="10" fill="#888">loop() runs thousands of times between events</text>
  <text x="380" y="222" text-anchor="middle" font-family="Manrope,sans-serif" font-size="10" fill="#c8c4bc">Each timer fires independently — none waits for the others</text>
</svg>

Fig 9.3: Three millis() timers at different rates. Sensor reads fire every 50 ms. Serial prints fire every 200 ms (4× the sensor interval, which keeps the monitor readable). The status LED toggles every 1000 ms. Between events, loop() runs freely, servicing Bluetooth, checking buttons, or doing anything else.

// Three independent timers — place these with your other globals
unsigned long lastSensorTime = 0;
unsigned long lastPrintTime  = 0;
unsigned long lastLedTime    = 0;
bool          ledState       = false;

const unsigned long SENSOR_INTERVAL = 50;   // 20 Hz
const unsigned long PRINT_INTERVAL  = 200;  // 5 Hz
const unsigned long LED_INTERVAL    = 1000; // 1 Hz

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

  // ── Sensor read (20 Hz) ───────────────────────────────────────────────────
  if (now - lastSensorTime >= SENSOR_INTERVAL) {
    lastSensorTime = now;
    long dist = readDistance();
    if (dist < STOP_DISTANCE_CM) stopMotors();
    else driveForward(CRUISE);
  }

  // ── Serial print (5 Hz — less output, monitor stays readable) ────────────
  if (now - lastPrintTime >= PRINT_INTERVAL) {
    lastPrintTime = now;
    Serial.print("dist="); Serial.println(lastDist);  // lastDist: global updated in sensor block
  }

  // ── Status LED blink (1 Hz) ───────────────────────────────────────────────
  if (now - lastLedTime >= LED_INTERVAL) {
    lastLedTime = now;
    ledState = !ledState;
    digitalWrite(LED_BUILTIN, ledState);
  }

  // ── Bluetooth (every loop iteration — no delay needed) ────────────────────
  if (btSerial.available() > 0) {
    char cmd = (char) btSerial.read();
    handleCommand(cmd);
  }
}

Notice that now is assigned once at the top of loop() and reused by all three timer checks. Don't call millis() separately inside each if block. A single assignment is consistent and slightly more efficient.

9.5 How fast does loop() actually run?

Without any delay(), loop() on an Arduino Uno runs tens of thousands of times per second under ideal conditions. Each iteration takes microseconds. The sensor timer fires every 50 ms, meaning loop() runs roughly 1000–5000 times between each sensor read doing nothing useful. That's fine. Empty iterations waste almost no time.

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

  <text x="380" y="22" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="11" letter-spacing="1" fill="#3d3c38">loop() ITERATION COST — no delay()</text>

  <!-- Bar chart: typical per-iteration time -->
  <!-- Axis -->
  <line x1="80" y1="160" x2="700" y2="160" stroke="#c4bfb0" stroke-width="1.5"/>
  <line x1="80" y1="40" x2="80" y2="160" stroke="#c4bfb0" stroke-width="1.5"/>
  <text x="68" y="164" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">0</text>
  <text x="68" y="100" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">1 ms</text>
  <text x="68" y="60" text-anchor="end" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">2 ms</text>
  <line x1="78" y1="100" x2="82" y2="100" stroke="#c4bfb0" stroke-width="1"/>
  <line x1="78" y1="60" x2="82" y2="60" stroke="#c4bfb0" stroke-width="1"/>

  <!-- Bars -->
  <!-- millis() check: ~4µs -->
  <rect x="100" y="159" width="60" height="1" rx="1" fill="#1a6b4a"/>
  <text x="130" y="176" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">millis()</text>
  <text x="130" y="152" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="8" fill="#1a6b4a">~4 µs</text>

  <!-- readDistance(): 2–30ms -->
  <rect x="200" y="60" width="60" height="100" rx="1" fill="#c8420a"/>
  <text x="230" y="176" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">readDist()</text>
  <text x="230" y="54" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="8" fill="#c8420a">2–30 ms</text>
  <text x="230" y="64" text-anchor="middle" font-family="Manrope,sans-serif" font-size="8" fill="#ffc0a0">(only every 50ms)</text>

  <!-- Serial.println: ~1ms -->
  <rect x="300" y="100" width="60" height="60" rx="1" fill="#1f4d8c"/>
  <text x="330" y="176" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">Serial.print</text>
  <text x="330" y="94" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="8" fill="#a0c0f0">~1 ms</text>
  <text x="330" y="104" text-anchor="middle" font-family="Manrope,sans-serif" font-size="8" fill="#7090c0">(only every 200ms)</text>

  <!-- btSerial.available: ~8µs -->
  <rect x="400" y="158" width="60" height="2" rx="1" fill="#7030d0"/>
  <text x="430" y="176" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">btSerial</text>
  <text x="430" y="152" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="8" fill="#9050f0">~8 µs</text>

  <!-- handleCommand: ~5µs -->
  <rect x="500" y="158" width="60" height="2" rx="1" fill="#8a6800"/>
  <text x="530" y="176" text-anchor="middle" font-family="Manrope,sans-serif" font-size="9" fill="#888">handleCmd</text>
  <text x="530" y="152" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="8" fill="#c8b400">~5 µs</text>

  <!-- Note -->
  <rect x="600" y="50" width="148" height="110" rx="4" fill="#1a1a18"/>
  <text x="674" y="70" text-anchor="middle" font-family="IBM Plex Mono,monospace" font-size="9" fill="#888">typical free loop()</text>
  <line x1="610" y1="77" x2="740" y2="77" stroke="#333" stroke-width="1"/>
  <text x="614" y="92" font-family="Manrope,sans-serif" font-size="9" fill="#c8c4bc">no sensors firing:</text>
  <text x="614" y="106" font-family="IBM Plex Mono,monospace" font-size="9" fill="#a8e8c8">~10–50 µs/iter</text>
  <text x="614" y="122" font-family="Manrope,sans-serif" font-size="9" fill="#c8c4bc">sensor firing:</text>
  <text x="614" y="136" font-family="IBM Plex Mono,monospace" font-size="9" fill="#c8420a">2–30 ms that iter</text>
  <text x="614" y="152" font-family="Manrope,sans-serif" font-size="9" fill="#888">BT always heard</text>
</svg>

Fig 9.4: Typical per-iteration cost. Most iterations take 10–50 µs (millis() check + btSerial.available()). Iterations where the sensor fires take 2–30 ms (the pulseIn() duration). readDistance() is still blocking internally because the sensor hardware requires it. millis() timers control when it fires, not how long it takes.

readDistance() itself is still blocking. pulseIn() inside it waits for the echo, and that wait is determined by physics, not code. The millis() pattern controls when you call readDistance(), not how long it takes. On the one iteration in 1000 where the sensor fires, the loop stalls for up to 30 ms. This is acceptable for a robot at walking speed. For higher-speed operation or tighter control loops, Module 12 covers interrupt-based sensing which eliminates this last blocking call.

9.6 Combining Bluetooth RC with sensor-guarded autonomy

The millis() pattern makes it straightforward to combine the RC control from Module 07 with the sensor check from Module 08. The robot accepts phone commands, but the sensor can override them if an obstacle is too close.

// ── Globals ───────────────────────────────────────────────────────────────────
#include <SoftwareSerial.h>
SoftwareSerial btSerial(2, 3);  // HC-05: RX=D2, TX=D3

unsigned long lastSensorTime  = 0;
unsigned long lastCommandTime = 0;  // dead-man timer from Module 7
long          lastDist        = 400;

const unsigned long SENSOR_INTERVAL  = 50;
const unsigned long COMMAND_TIMEOUT  = 500;  // stop if BT silent for 500ms

const int STOP_DISTANCE_CM = 20;
const int CRUISE           = 180;
const int RTRIM            = 0;   // update from your Module 5 calibration

// ── setup() ───────────────────────────────────────────────────────────────────
void setup() {
  // motor pins — same as Module 4
  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);
}

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

  // Sensor read at 20 Hz
  if (now - lastSensorTime >= SENSOR_INTERVAL) {
    lastSensorTime = now;
    lastDist = readDistance();
    // Safety override: stop if obstacle too close regardless of RC command
    if (lastDist < STOP_DISTANCE_CM) {
      stopMotors();
    }
  }

  // Bluetooth: check every loop iteration
  if (btSerial.available() > 0) {
    char cmd = (char) btSerial.read();
    lastCommandTime = now;
    // Only execute forward command if path is clear
    if (cmd == 'F' && lastDist < STOP_DISTANCE_CM) {
      // obstacle ahead — ignore forward, robot stays stopped
    } else {
      handleCommand(cmd);
    }
  }

  // Dead-man timer: stop if BT silent for 500 ms
  if (lastCommandTime > 0 && now - lastCommandTime > COMMAND_TIMEOUT) {
    stopMotors();
  }
}

This is the beginning of priority logic: the sensor can veto RC commands. The phone controls the robot, but the sensor protects it. Module 11 formalizes this into a full state machine with explicit RC and autonomous modes.

Advanced path: micros() for tight timing. millis() has 1 ms resolution. For timing events that need microsecond precision (such as the pulseIn() call itself or stepper motor pulse generation), use micros(), which returns elapsed time in microseconds. The same subtraction pattern applies: micros() - lastMicros >= interval_us. Be aware that micros() rolls over every ~70 minutes, and that interrupt-driven code can cause micros() to skip counts. For this course, millis() is sufficient for all timing needs.

Self-Check: Module 9


Key Terms Glossary

Term Definition
millis() Arduino function that returns the number of milliseconds elapsed since the microcontroller last powered on or was reset, as an unsigned long. Counts continuously without blocking.
non-blocking Code that checks a condition and returns immediately regardless of whether the condition is met. The opposite of blocking code (like delay()), which pauses execution until a condition is satisfied.
unsigned long A 32-bit unsigned integer type. Used for millis() return values because the counter can exceed 32767 (the limit of a plain int) after ~32 seconds of runtime. Stores up to ~4.3 billion.
timer variable A variable that stores the timestamp of the last time a timed action fired. Convention: prefix with last (e.g., lastSensorTime). Compare against millis() to determine elapsed time.
rollover When a counter exceeds its maximum value and wraps back to zero. millis() rolls over after ~49.7 days. Using subtraction (millis() - lastTime) handles rollover correctly because unsigned subtraction wraps around too.
loop rate The number of times loop() executes per second. Without delay(), a simple Arduino Uno loop runs tens of thousands of times per second. Adding sensors and serial reduces this but not to problematic levels.
priority logic Code structure where some conditions (e.g., a safety sensor) can override other conditions (e.g., RC commands). Implemented by checking the sensor result before deciding whether to execute the command.
dead-man timer A safety mechanism that stops the robot if no command is received within a defined timeout period. Prevents runaway if the control connection drops.

Hardware check before you start. Both motors should spin freely and the HC-SR04 should be reading distances correctly before you begin this module. Run the sensor-only test sketch from Module 08 and confirm you get smooth readings in Serial Monitor. If the sensor is misbehaving, diagnose it now. A hardware fault in Module 09 looks identical to a software bug, and you will spend a long time troubleshooting the wrong thing.

Lab 09: Replace delay() and add Bluetooth simultaneously

Upgrade the Module 08 obstacle-stop sketch to use millis() timers, then add Bluetooth RC control that the sensor can override. This is the first time both systems run in the same loop().

What you need: Completed robot from Module 08 (with HC-SR04 wired) · HC-05 module from Module 07 (already wired) · phone with Bluetooth terminal app

  1. Start with the Module 08 obstacle-stop sketch. Identify every delay() call. There should be one: delay(50) at the end of loop().

  2. Add unsigned long lastSensorTime = 0; to your globals. Add const unsigned long SENSOR_INTERVAL = 50; as a constant.

  3. Replace the delay(50) pattern: wrap the sensor read + motor decision block in a millis() interval check. Remove the delay(50). Upload and test. Robot behavior should be identical to Module 08.

  4. Open Serial Monitor. Notice the output is now 20 lines/second. That's the same rate as before. Try holding your hand in front of the sensor and moving it in and out quickly. The response should feel the same.

  5. Add a second timer: lastPrintTime at 200 ms. Move the Serial.print lines into this timer block only. Upload. Serial Monitor output should drop to 5 lines/second (still shows correct values, just less frequently).

  6. Wire the HC-05 as in Module 07 (it's probably already wired). Add the #include <SoftwareSerial.h>, btSerial(2, 3), and btSerial.begin(9600) declarations.

  7. Add the Bluetooth read block to loop(). Check btSerial.available() every iteration. Add the sensor override: if cmd == 'F' and lastDist < STOP_DISTANCE_CM, skip the forward command.

  8. Test: place the robot facing a wall 40 cm away. Send 'F' from the phone. Robot should drive toward the wall and stop at STOP_DISTANCE_CM. Send 'F' again and the robot should stay stopped (wall is too close). Send 'B' and the robot should drive backward. Send 'F' from farther away and the robot drives forward again.

  9. Stress test: hold the robot in your hand and rapidly send 'F', 'L', 'R', 'B' commands from the phone. The robot should respond immediately to each. No delay means no lag from commands queued up while the program was paused.

Module milestone: The robot accepts RC commands from the phone, reads the distance sensor at 20 Hz, and refuses forward commands when an obstacle is within STOP_DISTANCE_CM. All of this runs from a single loop() with no delay() calls. Serial Monitor shows clean, low-frequency output without flood. Ready for Module 10.


Previous: ← Module 08: Ultrasonic Distance Sensing · Next: Module 10: Obstacle Avoidance with State Machines →

Related Blog Posts