Logging to an SD memory card on a Teensy 4.1

While my robot “Raven” uses MicroRos to communicate between my TeensyMonitor board, which is based on a Teensy 4.1 device, there are times when software faults happen and the information I need to debug the fault doesn’t get transmitted as a ROS message. To overcome that, I have a software module on the TeensyMonitor board that logs a lot of information to an SD memory card. After a fault is detected, I can pull that memory card off from the TeensyMonitor board and plug it into another computer and look at the text log files for diagnostic information.

A problem with the built-in SD card on the Teensy 4.1, using the Arduino SD library is that the availableForWrite function always returns zero, so the example code for non-blocking I/O doesn’t work. This means that writes to the card necessarily block until complete. In a robot, any operation that takes a long time can be hazardous to the safety of the robot. In my library, while not eliminating the problem I attempt to reduce the problem by writing data in 4K byte chunks to the SD card. The result is that my average loop calls per second reduces from around 200 loop calls per second to about 175. This, of course, is specific to the work I do per loop call, which involves reading over a dozen sensors and sending as well as receiving messages via MicroRos.

A previous article explained my use of TModule in my software stack, which injects software module performance monitoring into each of my modules, so I won’t explain that framework again here. To use this logging module, you initialize it simply by including one line of code in you main “.ino” file, namely

TSd& sd = TSd::singleton();

Then you add lines to the log file via a call like:

TSd::singleton().log("INFO [MyModule::myFunction] Some message here");

Which will write to the log file a line similar to:

[0000111.428] INFO MyModule::myFunction] Some message here

Where the number in brackets is the number of milliseconds that have elapsed since the Arduino started up.

Here is the header file, “tsd.h” for the module:

#pragma once

#include <Regexp.h>
#include <SD.h>

#include "tmodule.h"

// A class used to write logging information to an SD memory card.
//
// On setup, the SD card is examined for any existing files with names like
// "LOG12345.TXT", where "12345" is a 5-digit serial number. A new log file
// will be created on the card with a name having a serial number of one higher
// than any existing log file name,or LOG00001.TXT if no existing log files
// were found.
//
// Every time TSd::singleton().log() is called, the message is added to a
// string buffer. When the buffer becomes full enough, it is written as one
// large chunck of text to the log file. This is done so that lots of little
// writes are done, which would slow down the outer loop of the Arduino device.
//
// The downside is that if the card is pulled from the Arduino device, the last
// chunk of text won't have been written to the device. Currently, there is a fair 
// number of things written to the log file so if you just wait a few seconds before
// pulling the card, the interesting thing you were looking for in the log file may
// have been actually successfully written to the file before you pulled the card.
//
// This is intended to be used the the TModule software module as part of the
// TeensyMonitor stack. So all you need to do to instantiate and get this module
// going is to call TSd::singleton() in your ".ino" file before calling TModule::setup().
//
// If a write to the card fails, perhaps because the card is full or the card has been
// pulled from the Arduino device, further writes are not attempted until the system
// is restarted.

class TSd : TModule {
 public:
  // Write message to log file.
  void log(const char* message);

  // Singleton constructor.
  static TSd& singleton();

 protected:
  // From TModule.
  void loop();

  // From TModule.
  virtual const char* name() { return "TSd"; }

  void setup();

 private:
  // Private constructor.
  TSd();

  static void regexpMatchCallback(const char* match, const unsigned int length,
                                  const MatchState& matchState);

  // Used to hold a big chunk of data so writes are fewer.
  String data_buffer_;

  // The SD card device.
  static SDClass g_sd_;

  // Used to find to highest log file number already on the SD card.
  static int g_highestExistingLogFileNumber_;

  // Has SD device been properly initialized?
  static bool g_initialized_;

  // The file handle for the log file on the SD card device.
  static File g_logFile_;

  // Singleton instance.
  static TSd* g_singleton_;
};

Here the the body file, “tsd.cpp”

#include "tsd.h"

#include <Arduino.h>
#include <Regexp.h>
#include <SD.h>
#include <stdint.h>

// #include "tmicro_ros.h"

void TSd::log(const char* message) {
  static const unsigned int kChunkSize = 4096;
  if (g_initialized_) {
    char log_message[256];
    uint32_t now = millis();
    snprintf(log_message, sizeof(log_message), "[%07ld.%03ld] %s\n", now / 1000,
             now % 1000, message);
    data_buffer_ += log_message;
    if (data_buffer_.length() >= kChunkSize) {
      size_t bytes_written = g_logFile_.write(data_buffer_.c_str(), kChunkSize);
      if (bytes_written > 0) {
        g_logFile_.flush();
      } else {
        // Assume the card has been removed or is failing.
        g_initialized_ = false;
      }

      data_buffer_.remove(0, kChunkSize);
    }
  }
}

void TSd::loop() {}

void TSd::regexpMatchCallback(const char* match, const unsigned int length,
                              const MatchState& matchState) {
  char regexMatchString[10];  // Big enough to hold 5-digit file serial number.
  matchState.GetCapture(regexMatchString, 0);  // Get 0-th match from regexp.
  int logSerialNumberAsInt = atoi(regexMatchString);
  if (logSerialNumberAsInt > TSd::g_highestExistingLogFileNumber_) {
    TSd::g_highestExistingLogFileNumber_ = logSerialNumberAsInt;
  }
}

void TSd::setup() {
  data_buffer_.reserve(8192);
  g_highestExistingLogFileNumber_ = 0;
  g_initialized_ = false;
  if (!g_sd_.begin(BUILTIN_SDCARD)) {
    // ERROR Unable to access builtin SD card.
  } else {
    File rootDirectory = g_sd_.open("/");
    while (true) {
      File nextFileInDirectory = rootDirectory.openNextFile();
      if (!nextFileInDirectory) break;
      char fileName[256];
      strncpy(fileName, nextFileInDirectory.name(), sizeof(fileName));
      MatchState matchState;
      matchState.Target(fileName);
      matchState.GlobalMatch("LOG(%d+).TXT", regexpMatchCallback);
    }

    char
        newLogFileName[20];  // Big enough to hold file name like: LOG12345.TXT.
    sprintf(newLogFileName, "LOG%05d.TXT", ++g_highestExistingLogFileNumber_);
    g_logFile_ = g_sd_.open(newLogFileName, FILE_WRITE);
    if (!g_logFile_) {
      char diagnosic_message[128];
      snprintf(diagnosic_message, sizeof(diagnosic_message),
               "ERROR [TSd::setup] Unable to create new log file: '%s'",
               newLogFileName);
    } else {
      g_initialized_ = true;
      ;
    }
  }
}

TSd::TSd() : TModule(TModule::kSd) {}

TSd& TSd::singleton() {
  if (!g_singleton_) {
    g_singleton_ = new TSd();
  }

  return *g_singleton_;
}

SDClass TSd::g_sd_;

int TSd::g_highestExistingLogFileNumber_ = 0;

bool TSd::g_initialized_ = false;

File TSd::g_logFile_;

TSd* TSd::g_singleton_ = nullptr;

Visualizing the noise in proximity sensors

My time-of-flight proximity sensors of my Raven (formerly Puck) robot use the VL53L0X chips and are fairly noisy. I wanted to have a quick way to visualize just how noisy they were. Here is the graph I produced:

Histograms for 8 time-of-flight sensors

The two rows represent the front versus back of the robot frame. The four columns represent the two pairs of sensors for the left and right sides of the robot frame. At each corner of the robot frame, there is a time-of-flight sensor that is pointed outward to the side (left or right) and another that is pointed either forward or backward. Each histogram is showing normalized counts per distance over the last sampling period.

As you can see from the histograms, some of the sensors are fairly noisy. This is with the robot not moving and nothing nearby is moving. Readings at 0 mm should be ignored as I moved all readings that were beyond 2 meters into the 0 meter bucket as they are uninteresting. The histogram in the third column of the first row shows a fairly wide variance in readings, while the histogram in the last column of the last row show a pretty narrow variance.

Below is the python code used to generate the plots. It includes code to read the ROS 2 messages generated by my custom monitor computer and uses matplotlib to do the display.

from datetime import datetime
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSHistoryPolicy

import matplotlib.pyplot as plt
import matplotlib.animation as animation
import numpy as np
from sensor_msgs.msg._range import Range
from std_msgs.msg import String

class MinimalSubscriber(Node):

    def __init__(self):
        super().__init__('minimal_subscriber')
        self.start_time = datetime.now()
        self.callback_count = 0

        # These are the title strings shown per sensor histogram.
        # They are a shortcut, for me, as to the physical position of the corresponding sensor.
        # The 'X" shows where the sensor is located. 
        # The '<' and '>' show whether the sensor is on the left or right side of the robot frame.
        # The '^' and 'v' show whether the sensor is on the front or rear of the robot frame.
        self.sensor_names = [['X<^-', '-<^X', 'X^>-', '-^>X'],
                             ['X<v-', '-<vX', 'Xv>-', '-v>X']]
        self.number_sensors = 8 # There are 8 sensors.
        self.number_values_to_cache = 20 # I want to show the variance over this number of the last readings.
        self.last_n_values_per_sensor = np.zeros(
            (self.number_sensors, self.number_values_to_cache), dtype='float')
        self.next_index_number = np.zeros((self.number_sensors), dtype='int32')

        # Create an array of histograms.
        # Two rows for front vs back of robot.
        # Four columns for left-sideways, left-front-or-back, right-front-or-back, right-sideways position.
        self.figure, self.axis = plt.subplots(
            nrows=2, ncols=4, sharex=False, sharey=False, squeeze=False, figsize=(8, 2))
        
        # Set the window title.
        self.figure.canvas.set_window_title('Time Of Flight Sensors step')

        # Create the x-axis values. I'm interested in only ranges from 0.00 to 1.00 meters.
        self.bins = [x / 100.0 for x in range(100)]

        # Make it all look pretty.
        plt.subplots_adjust(hspace=0.6)
        plt.autoscale(enable=True, axis='both', tight=True)
        plt.rcParams['lines.linewidth'] = 1

        # Set up the ROS 2 quality of service in order to read the sensor data.
        qos_profile = QoSProfile(
            reliability=QoSReliabilityPolicy.BEST_EFFORT,
            history=QoSHistoryPolicy.KEEP_LAST,
            depth=1
        )
        
        # Subscribe to the sensor topics.
        for sensor_number in range(8):
            self.subscription = self.create_subscription(
                Range,
                '/tof{s}Sensor'.format(s = sensor_number),
                self.listener_callback,
                qos_profile,
            )

        # Set up the 8 histogram formats and titles.
        self.patches = [1, 2, 3, 4, 5, 6, 7, 8]
        for row in range(2):
            for col in range(4):
                n, bins, patches = self.axis[row][col].hist(
                    self.last_n_values_per_sensor[row][col], self.bins, histtype='bar')
                self.patches[(row * 4) + col] = patches
                self.axis[row, col].set_title(
                    self.sensor_names[row][col], fontsize=8, fontfamily='monospace')
        
        # Let's go.
        plt.ion()
        plt.show()
        
        self.subscription  # prevent unused variable warning


    # Process a time-of-flight sensor message of type Range.
    def listener_callback(self, msg):
        self.callback_count = self.callback_count + 1
        sensor_number = int(msg.header.frame_id[-1])    # Get the sensor number.
        range_value = msg.range
        if (range_value > 2.0):
            # If the range is greater than 2 meters, ignore it by setting it to zero.
            range_value = 0
            
        # Capture the last readings of the sensor in a ring buffer.
        self.last_n_values_per_sensor[sensor_number][self.next_index_number[sensor_number]] = range_value

        if (self.callback_count % 24) == 0:
            # Peridically update the plots.
            for s in range(8):
                # For each sensor, create a histogram.
                data = self.last_n_values_per_sensor[s]
                n, _ = np.histogram(data, self.bins, density=True)
                max = n.max()
                for count, rect in zip(n, self.patches[s]):
                    rect.set_height(count / max) # Normalize the height of the rectangle.
            self.figure.canvas.draw()
            self.figure.canvas.flush_events()
            
            # Print out the frames per second of sensor data for all 8 sensors since the last plot update.
            # Divide by 8 if you want to know the frames per second per sensor.
            duration = datetime.now() - self.start_time
            fps = self.callback_count / (duration.seconds + (duration.microseconds / 1000000.0))
            print("callback_count: %d, duration: %f, fps: %3.2f" % (self.callback_count, (duration.seconds + (duration.microseconds / 1000000.0)), fps))

        # Update the ring buffer index.
        self.next_index_number[sensor_number] = self.next_index_number[sensor_number] + 1
        if self.next_index_number[sensor_number] >= self.number_values_to_cache:
            self.next_index_number[sensor_number] = 0

def main(args=None):
    rclpy.init(args=args)

    minimal_subscriber = MinimalSubscriber()

    rclpy.spin(minimal_subscriber)

    minimal_subscriber.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

Replacing the Arduino setup/loop Mechanism

Arduino-like processors are programmed with a setup and loop mechanism. The function setup is called once by the underlying firmware, and then loop is called repeatedly after that. I created a TModule class that I use to extend/replace/wrap those functions (choose how you want to think about it). This primarily gives me the ability to keep track of the performance of each piece of software that I write.

My robot uses a Teensy 4.1 microprocessor, and a custom PC board that I designed, into which that Teensy 4.1 is plugged in and which then extends all the I/O of the Teensy in a useful way. For instance, I use one of the Teensy 4.1 I2C channels along with an I2C multiplexer to talk to the eight time-of-flight sensors on the robot. The HC-SR04 SONAR sensors require level converters to translate the 3.3 volt I/O pins of the Teensy to the 5 volt pins of the SONAR sensors. And so on. My robot uses nearly every I/O pin on the Teensy.

The software on the Teensy, which I call the Teensy Monitor, is organized around modules. For instance, there is a SONAR module, a time-of-flight module, a module to talk to the RoboClaw motor controller, a module to communicate with the other processors on the robot using micro-ROS, and so on. For each of these modules, I need to see if there are any hardware failures and I need to see if they are performing as expected.

For example, it’s possible that one of the time-of-flight sensors isn’t working correctly. It’s possible that one of the motor current sensors isn’t responding. It’s possible that some module is taking too long to operate, which might then effect how often the main processor of the robot gets SONAR data, which might make the robot operate in an unsafe manner.

My TModule class handles the performance monitoring part of all of this.

The way you use TModule is that each software module is a class that derives from TModule. As each software module class is instantiated, the instance is added to a list of all instantiated modules. TModule has a DoSetup method that, when called, will call setup for each instantiated module. And TModule has a DoLoop method that, when called, will call the loop method for each instantiated module, but it wraps that loop call with code that will measure the duration of the loop call.

For each software module, statistics are capture for the minimum, maximum and average execution duration of the loop call. There is a method in TModule that returns a JSON string showing the statistics for every instantiated module. My module that uses micro-ROS has a method that periodically gets the statistics from TModule and sends that JSON string to the ROS system on the robot. Asking for the statistics from TModule also resets the statistics. So each JSON message shows the performance of every instantiated module since the last reported performance.

Here is what a JSON statistics report looked like at one point in my software development:

{
  "Stats": {
    "loops": 211,
    "Ms": 999.8,
    "mdls": [
      { "n": "Alrm", "MnMxAv": [0.0, 0.0, 0.0] },
      { "n": "uRos", "MnMxAv": [0.2, 1.6, 1.3] },
      { "n": "Amps", "MnMxAv": [1.0, 1.0, 1.0] },
      { "n": "Rlay", "MnMxAv": [0.0, 0.0, 0.0] },
      { "n": "Robo", "MnMxAv": [0.6, 1.2, 0.8] },
      { "n": "Sonr", "MnMxAv": [0.0, 0.0, 0.0] },
      { "n": "Temp", "MnMxAv": [0.0, 0.0, 0.0] },
      { "n": "ToFl", "MnMxAv": [1.6, 1.7, 1.6] }
    ]
  }
}

This says that since the last reported statistics, the Arduino loop method was called 211 times and it took 999.8 milliseconds to execute those 211 calls. The 999.8 milliseconds period is because the micro-ROS module is set up to report statistics every second. This message lets me know that in the last second, the SONAR module was called 211 times, the time-of-flight module was called 211 times, and so on.

Each module subclass has a name method that returns a short string naming the module. That value shows after the “n” keyword above. So, the module that talks to the RoboClaw is named Robo, and over the last 211 times the RoboClaw module had its loop method called, the minimum execution time of a loop call was 0.6 milliseconds. The maximum loop call duration was 1.2 milliseconds, and the average call duration was 0.8 milliseconds. If I wanted to increase the overall number of loop calls per second, I should first look at improving the modules with the largest maximum or average duration, such as the micro-ROS loop method, called uROS in the report, as its average execution duration is 1.3 milliseconds, or the time-of-flight module, called ToFl in the report, as its average execution duration is 1.6 milliseconds.

The header file, tmodule.h is:

#pragma once

#include <stdint.h>

#include "Arduino.h"

/**
 * Base class for a kind of module which:
 *  - Needs to be setup once via a call to DoSetup().
 *  - Needs to be invoked once per "processing cycle" via a call to DoLoop().
 *  - Generates performance statistics gathered about performance during loop
 * execution.
 *
 * Usage:
 * Each module exists as a singleton. Somewhere, modules are
 * brought into existence by calling, typically, their
 * singleton() method. As each module comes into existence,
 * This TModule class keeps a list of them.
 *
 * After all modules are brought into existence, you call the
 * DoSetup() method to invoke the setup() method for all registered
 * modules. Then in the main processing loop, you invoke the
 * DoLoop() method to invoked the loop() method for all registered
 * modules.
 * 
 * Periodically, some agent calls GetStatistics() to get a string showing
 * execution performance of all the registered modules.
 */

class TModule {
 public:
  // A list of all possible modules.
  typedef enum Module {
    kMicroRos, // Make this the first module as it is used for diagnostic reporting.
    kMotorCurrent,
    kPanelSelector,
    kRelay,
    kRoboClaw,
    kSonar,
    kTemperature,
    kTimeOfFlight,
    kNumberModules  // The number of all possible modules.
  } Module;

  // Call loop() for all registered modules.
  static void DoLoop();

  // Call setup() for all registered modules.
  static void DoSetup();

  // Get a JSON string showing module performance since the
  // last call to GetStatistics.
  static void GetStatistics(char* outString, size_t outStringSize);

 protected:
  TModule(Module moduleKind);

  // Perform regular, cyclic work for the module.
  virtual void loop() = 0;

  // Return module name.
  virtual const char* name() = 0;

  // Perform one-time setup for the module.
  virtual void setup() = 0;

 private:
  TModule();

  // Define slots for gathering statistics for the module.
  typedef enum Slot {
    kMin,
    kMax,
    kSum,
    kNumberSlots            // Number of slots to reserve for statistics.
  } Slot;

  // Number of times DoLoop() was called.
  static uint32_t total_do_loop_count_;

  // A list of all registered modules.
  static TModule* all_modules_[];

  // Index to the next statistic reading for the module.
  int loop_calls_between_get_statistics_calls_;

  // Statistics gathered per registered modules.
  float duration_stats_[kNumberSlots];
};

The body code file tmodule.cpp

#include "tmodule.h"

#include <Arduino.h>
#include <stdint.h>

#include "tmicro_ros.h"

TModule::TModule(TModule::Module moduleKind) {
  all_modules_[moduleKind] = this;
  loop_calls_between_get_statistics_calls_ = 0;
  for (size_t i = 0; i < kNumberSlots; i++) {
    duration_stats_[i] = 0.0;
  }
}

void TModule::GetStatistics(char* outString, size_t outStringSize) {
  static uint32_t statTimingStart = micros();
  char statList[2048];

  statList[0] = '\0';

  for (size_t i = 0; i < kNumberModules; i++) {
    if (all_modules_[i] != nullptr) {
      TModule* module = all_modules_[i];
      char temp[512];
      temp[0] = '\0';
      snprintf(temp, sizeof(temp),
               "{\"n\":\"%-s\",\"MnMxAv\":[%-2.1f,%-2.1f,%-2.1f]},",
               module->name(), module->duration_stats_[kMin],
               module->duration_stats_[kMax],
               module->duration_stats_[kSum] / total_do_loop_count_);
      strcat(statList, temp);
      module->loop_calls_between_get_statistics_calls_ = 0;
      module->duration_stats_[kMin] = 10'000'000.0;
      module->duration_stats_[kMax] = -10'000'000.0;
      module->duration_stats_[kSum] = 0.0;
    }
  }

  // Remove trailing comma from previous list.
  if (strlen(statList) > 0) {
    statList[strlen(statList) - 1] = '\0';
  }

  snprintf(outString, outStringSize,
           "{\"loops\":%-ld,\"Ms\":%-2.1f,\"mdls\":[%-s]}",
           total_do_loop_count_, ((micros() * 1.0) - statTimingStart) / 1000.0,
           statList);
  statTimingStart = micros();
  total_do_loop_count_ = 0;
}

void TModule::DoLoop() {
  for (size_t i = 0; i < kNumberModules; i++) {
    if (all_modules_[i] != nullptr) {
      TModule* module = all_modules_[i];
      uint32_t start = micros();

      all_modules_[i]->loop();

      float duration = (micros() - start) / 1000.0;
      module->duration_stats_[kSum] += duration;
      if (duration < module->duration_stats_[kMin]) {
        module->duration_stats_[kMin] = duration;
      }

      if (duration > module->duration_stats_[kMax]) {
        module->duration_stats_[kMax] = duration;
      }

      module->loop_calls_between_get_statistics_calls_++;
    }
  }

  total_do_loop_count_++;
}

void TModule::DoSetup() {
  for (int i = 0; i < kNumberModules; i++) {
    if (all_modules_[i] != nullptr) {
      all_modules_[i]->setup();
    }
  }
}

TModule* TModule::all_modules_[TModule::kNumberModules + 1] = {
    nullptr, nullptr, nullptr, nullptr, nullptr,
    nullptr, nullptr, nullptr};

uint32_t TModule::total_do_loop_count_ = 0;

This is all driven by code in the main ino file for the Arduino-like system, where each module of interest is instantiated, then DoSetup and DoLoop are called as shown.

#include <stdint.h>

#include "tmicro_ros.h"
#include "tmodule.h"
#include "trelay.h"
#include "troboclaw.h"
#include "tsonar.h"
#include "ttemperature.h"
#include "ttime_of_flight.h"

// Initialize all TModule instances in any required order.
TMicroRos& micro_ros = TMicroRos::singleton();
TRelay& relay = TRelay::singleton();
TRoboClaw& roboclaw = TRoboClaw::singleton();
TSonar& sonar = TSonar::singleton();
TTemperature& temperature = TTemperature::singleton();
TTimeOfFlight& time_of_flight = TTimeOfFlight::singleton();

void setup() {
  TModule::DoSetup();
}

void loop() {
  TModule::DoLoop();
}

Efficient multi-SONAR with Arduino-like systems

Handling multiple sensors on an Arduino-like processor, specifically a Teensy 4.1 in my case, can be a bit tricky if you want to get high loop rates.

In my robot, I’m using the Teensy to send data from 8 time-of-flight sensors, 4 SONAR sensors, 2 motor current sensors and 2 motor temperature sensors while also controlling a RoboClaw motor controller, an 8-channel relay board and a touch screen display. On top of this, it runs micro-ROS to send and receive data messages to the rest of the robot.

In this article I will talk only about the issue of using the HC-SR04, inexpensive SONAR sensors. Here is one article that gives you some background in what the sensor is and how it works.

For a robot that uses the ROS software stack, getting data at fast frame rates is crucial, otherwise the robot will have moved far along from where it was when the sensor data was gathered, so the data no longer represents the truth from the point where the robot is now.

It can take on order of 20 milliseconds to get a reading from the SONAR at the maximum distance. If you had a single sensor and read it once per loop, you could, in theory, send about 50 readings a second to your robot. With 4 sensors, however, if you sensed one SONAR after the other in a round-robin manner, the frame rate would drop down to about 50/4 or 12.5 frames per second, which may be too low a rate for your robot.

If your robot is moving at the rate of a slow walk for a person, about 1 mile per hour, that translates to 0.45 meters per second. At a frame rate of 12.5 frames per second, the robot will move 36 millimeters or about 1.4 inches between readings. If you are traveling along a narrow hallway or in a crowded room, that may not be good enough to avoid crashing into nearby obstacles. If you can get back up to nearly 50 frames per second, though, the robot will only travel about 9 millimeters or just over a third of an inch. Add in the other things your Arduino processor is doing besides reading SONAR sensors and frame rates could get much worse.

To get around this problem, you need to use interrupt handlers to control the SONAR sensors. Briefly, what I do is:

  • Use a timer to drive a state machine. The timer generates an interrupt every 20 microseconds.
  • The timer handler has a counter. Every 500 counts, or 500 * 20 microseconds which is 0.01 seconds, the next SONAR in the set of 4 begins a reading. I used this fixed spacing to solve the issue of multiple SONARs interfering with each other. Whenever a SONAR begins sending its ping sound, it’s possible for all the other SONAR sensors to receive the echo. I want to make it pretty likely that a SONAR hears only its own echo. Sound travels at about 340 meters per second. In 0.01 seconds, a SONAR ping can travel about 3.4 meters. Since SONAR measures round-trip time delay, the SONAR can detect objects up to about 1.7 meters in that 0.01 seconds. Practically, the HC-SR04 sensors are not so accurate or sensitive after about that distance, anyway.
  • Once a SONAR starts transmitting its ping, 20 microseconds later the transmitter is turned off. Then the next SONAR in the set of 4 will get the on/off sequence after 0.01 seconds.
  • When the transmitter stops for a SONAR, it begins listening for the echo. The echo is processed via an interrupt handler. The interrupt handler computes the time it took to hear the echo, uses the speed of sound to convert echo time to the distance to the obstacle. Then a ROS message is sent for the sensor reading.

On a Teensy4.1, my code is publishing about 25 frames per second for each of the 4 SONAR sensors, or 100 frames per second alltogether. The sensors are spaced out in time, the readings don’t come altogether at once, as described above. Also, the whole code is driven by my TModule code module, which I’ll describe in another article, but you can take this code by itself and combine the two loop and setup methods together and run it without my TModule module.

Here is tsonar.h

#pragma once

#include <Wire.h>
#include <stdint.h>

#include "tmodule.h"

class TSonar : TModule {
 public:
  // Which SONAR sensor.
  typedef enum Sonar {
    kFront,
    kRight,
    kBack,
    kLeft,
    kNumberSonars  // Number of SONAR sensors.
  } Sonar;

  // Get sensed range for the device. A value of < 0 => no sensor 'device'
  // detected during setup.
  int GetValueMm(Sonar device);

  // Get the average range for the device.
  float GetAverageValueM(Sonar device);

  // Singleton constructor.
  static TSonar& singleton();

 protected:
  // From TModule.‰
  void loop();

  // From TModule.‰
  const char* name() { return "Sonr"; }

  // From TModule.‰
  void setup();

 private:
  // Number of readings to average together to reduce noise.
  static const uint8_t kNumberReadingsToAverage = 4;

  // Private constructor.
  TSonar();

  // Common interrupt handler.
  static void CommonInterruptHandler(uint8_t pin, long& end_time,
                                     long& start_time, uint8_t& average_index,
                                     size_t sonar_index);

  // Interrupt handler for per device echo.
  static void Echo0InterruptHandler();
  static void Echo1InterruptHandler();
  static void Echo2InterruptHandler();
  static void Echo3InterruptHandler();
  static void TimerInterruptHandler();

  // Next device being handled in the round-robin processing.
  static uint8_t g_next_sensor_index_;

  // Singleton instance.
  static TSonar* g_singleton_;

  // Last captured sensed distance for each SONAR device.
  static int g_values_mm_[kNumberSonars];

  // List of last values, for computing an average.
  static int g_values_mm_history_[kNumberSonars][kNumberReadingsToAverage];

  // Last captured average distance for each SONAR device.
  static float g_average_value_m_[kNumberSonars];

  // GPIO pins for controlling the SONAR sensors.
  enum {
    kPinEcho0 = 35,
    kPinTrigger0 = 34,
    kPinEcho1 = 37,
    kPinTrigger1 = 36,
    kPinEcho2 = 41,
    kPinTrigger2 = 40,
    kPinEcho3 = 15,
    kPinTrigger3 = 14
  };

  // Microseconds per timer interrupt.
  static const uint16_t kTimerPeriodUSec = 20;

  // Desired milliseconds to wait between a low pulse and the next high pulse.
  static const uint16_t kTimerSamplingPeriodMSec = 10;

  // Timer interrupts to expire before a low pulse to high pulse transition is
  // taken..
  static const uint16_t kTimerCountsPerSamplingPeriod =
      (kTimerSamplingPeriodMSec * 1000) / kTimerPeriodUSec;

  // For converting SONAR echo time to millimeters.
  static const float g_time_to_mm_scaler_;
};

And here is tsonar.cpp

#include "tsonar.h"

#include <stdint.h>

#include "Arduino.h"
#include "TimerOne.h"
#include "Wire.h"
#include "tmicro_ros.h"

void TSonar::CommonInterruptHandler(uint8_t pin, long& end_time,
                                    long& start_time, uint8_t& average_index,
                                    size_t sonar_index) {
  switch (digitalRead(pin)) {
    case HIGH:
      // When the SONAR begins transmitting, the echo pin will
      // go HIGH. Capture the start time.
      end_time = 0;
      start_time = micros();
      break;

    case LOW:
      // When an echo is received, the echo pin will go LOW.
      // Compute the distance to the object and send a ROS message.
      end_time = micros();
      g_values_mm_[sonar_index] =
          (end_time - start_time) * g_time_to_mm_scaler_;
      g_values_mm_history_[sonar_index][average_index++] =
          g_values_mm_[sonar_index];
      if (average_index >= kNumberReadingsToAverage) {
        average_index = 0;
      }

      // Compute an average distance over the last few readings
      // to help reduce the sensor noise.
      int average_sum_mm = 0;
      for (size_t i = 0; i < kNumberReadingsToAverage; i++) {
        average_sum_mm += g_values_mm_history_[sonar_index][i];
      }

      g_average_value_m_[sonar_index] =
          (average_sum_mm * 0.001) / kNumberReadingsToAverage;

      // Publish the average distance for the sensor.
      TMicroRos::PublishSonar(sonar_index, g_average_value_m_[sonar_index]);
      break;
  }
}

float TSonar::GetAverageValueM(Sonar device) {
  return g_average_value_m_[device];
}

void TSonar::Echo0InterruptHandler() {
  // Each sensor has it's own distance timer and it's own
  // set of values used to compute an averate distance.
  static long end_time = 0;
  static long start_time = 0;
  static uint8_t average_index = 0;
  CommonInterruptHandler(kPinEcho0, end_time, start_time, average_index, 0);
}

void TSonar::Echo1InterruptHandler() {
  static long end_time = 0;
  static long start_time = 0;
  static uint8_t average_index = 0;
  CommonInterruptHandler(kPinEcho1, end_time, start_time, average_index, 1);
}

void TSonar::Echo2InterruptHandler() {
  static long end_time = 0;
  static long start_time = 0;
  static uint8_t average_index = 0;
  CommonInterruptHandler(kPinEcho2, end_time, start_time, average_index, 2);
}

void TSonar::Echo3InterruptHandler() {
  static long end_time = 0;
  static long start_time = 0;
  static uint8_t average_index = 0;
  CommonInterruptHandler(kPinEcho3, end_time, start_time, average_index, 3);
}

int TSonar::GetValueMm(Sonar device) {
  if (static_cast<int>(device) >= kNumberSonars) {
    return -1;
  } else {
    return g_values_mm_[static_cast<int>(device)];
  }
}

void TSonar::loop() {
  // Nothing needs to be done in the loop. Everything is drivven
  // by interrupts.
}

void TSonar::setup() {
  // Set up the Teensy pins to talk to the SONAR devices.
  pinMode(kPinEcho0, INPUT);
  pinMode(kPinTrigger0, OUTPUT);
  pinMode(kPinEcho1, INPUT);
  pinMode(kPinTrigger1, OUTPUT);
  pinMode(kPinEcho2, INPUT);
  pinMode(kPinTrigger2, OUTPUT);
  pinMode(kPinEcho3, INPUT);
  pinMode(kPinTrigger3, OUTPUT);

  // Setup a timer to drive the state machine.
  Timer1.initialize(kTimerPeriodUSec);
  Timer1.attachInterrupt(TimerInterruptHandler);

  // Attach an interrupt handler to each SONAR's echo pin.
  attachInterrupt(kPinEcho0, Echo0InterruptHandler, CHANGE);
  attachInterrupt(kPinEcho1, Echo1InterruptHandler, CHANGE);
  attachInterrupt(kPinEcho2, Echo2InterruptHandler, CHANGE);
  attachInterrupt(kPinEcho3, Echo3InterruptHandler, CHANGE);
}

void TSonar::TimerInterruptHandler() {
  // The states of the state machine.
  typedef enum {
    COUNTDOWN,   // Count down timer ticks.
    PULSE_HIGH,  // Begin transmitting the SONAR pulse.
    PULSE_LOW  // Stop transmitting the SONAR pulse and begin listening for the
               // echo.
  } TTimerState;

  // The current state of the state machine.
  static volatile TTimerState state = COUNTDOWN;

  // Used to count timer pulses to drive the timing of each SONAR sensor.
  static volatile long countdown = kTimerCountsPerSamplingPeriod;

  if (--countdown == 0) {
    // Time to start the next SONAR sensor in the list of sensors.
    state = PULSE_HIGH;
    countdown = kTimerCountsPerSamplingPeriod;
  }

  switch (state) {
    case COUNTDOWN:
      // Continue counting so that the sensors are spaced
      // apart in time so they don't interfere with each other.
      break;

    case PULSE_HIGH:
      // Time to send out the ping for the next SONAR in the list.
      if ((g_next_sensor_index_ % 4) == 0) {
        digitalWrite(kPinTrigger0, HIGH);
      } else if ((g_next_sensor_index_ % 4) == 1) {
        digitalWrite(kPinTrigger1, HIGH);
      } else if ((g_next_sensor_index_ % 4) == 2) {
        digitalWrite(kPinTrigger2, HIGH);
      } else {
        digitalWrite(kPinTrigger3, HIGH);
      }

      state = PULSE_LOW;
      break;

    case PULSE_LOW:
      // Time to stop the ping output and begin listening for the
      // echo for the next SONAR in the list.
      if ((g_next_sensor_index_ % 4) == 0) {
        digitalWrite(kPinTrigger0, LOW);
      } else if ((g_next_sensor_index_ % 4) == 1) {
        digitalWrite(kPinTrigger1, LOW);
      } else if ((g_next_sensor_index_ % 4) == 2) {
        digitalWrite(kPinTrigger2, LOW);
      } else {
        digitalWrite(kPinTrigger3, LOW);
      }

      g_next_sensor_index_++;  // Control the next sensor in the list the next
                               // time around.
      state = COUNTDOWN;       // Begin counting down again.
      break;
  }
}

TSonar::TSonar() : TModule(TModule::kSonar) {
  for (size_t i = 0; i < kNumberSonars; i++) {
    // Initialize the array of readings used to computer the average distance
    // per sensor.
    for (size_t j = 0; j < kNumberReadingsToAverage; j++) {
      g_values_mm_history_[i][j] = 0;
    }
  }
}

TSonar& TSonar::singleton() {
  // A singleton pattern is used to support the TModule design pattern.
  if (!g_singleton_) {
    g_singleton_ = new TSonar();
  }

  return *g_singleton_;
}

uint8_t TSonar::g_next_sensor_index_ =
    0;  // Which sensor in the list is being controlled now.

TSonar* TSonar::g_singleton_ =
    nullptr;  // Used to ensure that only one instance of this class is ever
              // constructed.

int TSonar::g_values_mm_[TSonar::kNumberSonars] = {
    -1, -1, -1, -1};  // The last reading per sensor.

int TSonar::g_values_mm_history_
    [TSonar::kNumberSonars]
    [TSonar::kNumberReadingsToAverage];  // List of readings per sensur used to
                                         // computer an average per sensor.

float TSonar::g_average_value_m_[TSonar::kNumberSonars] = {
    0, 0, 0, 0};  // The computed average distance per sensor.

const float TSonar::g_time_to_mm_scaler_ =
    (10.0 / 2.0) / 29.1;  // For converting time to distance.

2022 11 02 Puck Status

The big result since the last status report is that more, very important safety systems have been implemented to protect the robot and its surroundings, and the robot now has more data about objects near to it as it moves so it can avoid running into those obstacles. And the new power and data control panel is finished, which makes it easier for me to disassemble the robot.

The last week and a half has seen a lot of work on Puck. Two of the time of flight sensors were replaced as the originals were either not sending distance measurements or the measurements were wildly wrong. While that layer of the physical robot case was opened to replace the sensors, I also color-coded all the cables for the time of flight and SONAR sensors, making it easier to trace the cables from the custom micro processor board (a.k.a the Teensy Monitor Board) to the physical sensors. The new power and data control panel was finished and all the new wiring is in place.

I also rewired the signal cable from the relay block to the emergency stop of the motor controller. This would allow the Teensy Monitor to immediately stop power going to the motors if some emergency situation were discovered.

A lot of work was done in the software of the Teensy Monitor. More diagnostic messages were added, which showed that there are still reliability issues with communication between the Teensy Monitor and the sensors, which is something I’ll have to solve eventually. I may just need to add better cable shielding.

The motor temperature sensors now are published to a topic, and the temperature values are now averaged as the sensors tend to be rather noisy. Code was added to detect an over-temperature situation for the motors. When the robot is driven for a long time, the temperature inside the motors can build up to the point that there is a risk of melting the wires inside.

Importantly, code to detect a runaway motor situation is now implemented. This happens especially when the encoder connections to the motor controller come loose. Remember that the robot vibrates a lot when it moves, and the connectors on the RoboClaw motor controller are not designed to stay well connected in the face of vibration.

The redundant motor current sensors were found to be useless, so the code that talked with those sensors is disabled for now. I’ll need to find some better sensors in the future. Meanwhile the motor current sensors built into the RoboClaw are working well enough. And code was added to detect an over-current situation, which can happen when the robot runs up against, say, a wall and the motor wheels stop turning or turn very slowly. Left in this situation, the wires in the motor would quickly overheat and literally melt.

With the three new fault detection code routines, the robot now get shut off via the emergency-stop signal to the RoboClaw if the motors get too hot, if the motors take off at high speed unexpectedly, or if the motors start drawing a lot of current, beyond normal operation. This is a three way protection to save the expensive motors and prevent the robot from running into something and just keep pushing forward.

With the now fully working SONAR and time of flight sensors, and the data being published at 25 to 30 frames per second, I finally figured out how to hook those sensors into the robot motion planning software. Now, if the robot is moving along and comes across an obstacle that only one of the proximity sensors can see (the LIDAR sees objects only at a specific height), the robot can make a plan to move around the object.

Outstanding work remains to discover why some of the sensor values are occasionally rejected by the planning software. It is likely that is because the data is too old, meaning that the data was more than a couple of milliseconds old by the time the planning software saw it. There may be a simple fix, but it needs to be investigated.

Teensy Monitor Board

Teensy Monitor Board and 8-Channel Relay Board

Overview of the Teensy Monitor Board

A custom PC board was built to use a Teensy 4.1 Development Board as a base and control a lot of sensors and otherwise monitor the health of the robot. I call this board the Teensy Monitor Board.

It controls eight VL53L0X time of flight sensors used as proximity sensors, four HC-SR04 sonar sensors used as proximity sensors, a pair of I2C-bus motor current sensors, a color touchscreen, two analog motor temperature sensors, an 8-channel relay board, an Ethernet connector, and a serial UART connection to the RoboClaw motor controller. Additionally, there is a spare port for either another analog sensor or another serial UART connection, and a pair of SPI-bus ports that were originally intended to be used for motor current sensors.

The monitor board collects all of the sensor information and publishes it as a JSON message via the Ethernet connection. It also reads a status message from the primary computer. If the monitor detects an unexpected situation, it is able to shutdown the motors.

A block diagram overview of the Teensy Monitor Board

The monitor also reads the status of the RoboClaw motor controller and compares the status of the motors to the expected status as reported by the main processor.

The touchscreen display shows the status of all of the sensors on one panel, and the other panel provides a way to power off and on the primary and secondary computers or to reset either of those computers. It can also power off and on the RoboClaw motor controller.

An unexpected situation, which might cause the monitor to shut down the motors, occurs if any of the following is detected:

  • The current in either motor is out of range. Currents are read via the connection to the RoboClaw motor controller and, redundantly, by current sensors inline with the motor power. If any motor should stall or even be slowed down by an external force, the motor current spikes and could result in a meltdown of the winding.
  • The speed of either motor is significantly different than that commanded by the computers via the navigational software, an external game controller or a virtual keyboard teleoperation device.
  • The temperature of either motor is out of range. Even if the current to the motors stays within a safe range, over time the motors could gradually heat up to an unsafe temperature where the windings could short of melt.
  • The time of flight or sonar sensors detect that the robot is too near an object. The navigational software should have prevented the robot from getting too close.
  • The heartbeat timer or other status from the computers is out of range. This can occur especially if software crashes on either of the two computers.

The Touchscreen Display

The sensor status panel of the touchscreen display

The touchscreen display shows one of two different panels, selected by touching either the “POWER” or “SENSE” boxes in the upper right of the display.

The SENSE panel displays:

  • The eight time of flight sensor values. The sensors are mounted in pairs on each corner of the robot. The display shows the value of each sensor corresponding to the physical position of the sensor. For instance, the red value “0.049” above is showing the sensor distance, in meters, for the sensor that is mounted at the front left corner of the robot, facing forward. The value “0.255” above is showing the sensor distance for the sensor that is mounted in the back right corner of the robot, facing to the right. As a result, the eight sensors provide two forward looking, two backward looking, two left looking and two right lookng sensors.

    If the display value is white, the sensed distance is considered within the range that the navigational software should be able to deal with. If the value is red, an object or surface has gotten too close to one of the corners of the robot. If “rng” is shown as the value, then the range is far enough out to not be of interest to the monitor board.
  • The four sonar values. The sensors are mounted in the middle of the front, back, left and right sides of the robot. The same white/red rules apply as for the time of flight sensors. The LASER powered time of flight sensors have their pluses and minuses as to what kinds of objects they can detect, and the ultrasonic sonar sensors have a different set of pluses and minus. To provide extra projection, these two kinds of sensors somewhat overlap in detecting that the robot has gotten somewhere it shouldn’t have.
  • The two motor currents. The RobotClaw motor controller provides a readout of the motor currents, but it doesn’t always agree with independent observation. An extra pair of motor current sensors is provided as a redundant set of eyes. If the motor is pushing on something so the wheels are laboring or, worse, if the wheels stop turning altogether, the current in the motors can spike high enough to melt the wire windings.
  • The two motor temperatures. The motors can overheat either through gradual means from normal operation at high but expected current, from external causes such as radiation from the sun or from driving over a hot surface. Regardless of the cause, if the motor windings get too hot, they can short out or melt.
The power control panel of the touchscreen display

When the POWER panel is selected, you can turn on or off the power to the primary computer, the secondary computer or the RoboClaw motor controller. You can also reset the primary or secondary computer

The schematics of the Teensy Monitor Board can be seen here.