Skip to content

Initial EMG Algorithm

Oliver Vogel-Reed edited this page May 31, 2019 · 6 revisions

Introduction

Note that this document is current as of commit 7dc8be1. It probably makes sense to do additional algorithm work in a new sketch, and leave InitialDetectorAlgorithm.ino intact as a working prototype.

The EMG sensor provides an analog voltage that we need to convert into a suitable binary triggering signal for the hand. The simplest approach would be a threshold, but we have observed noise, offsets and varying signal levels in the analog EMG voltage. Something a little more sophisticated is needed, but it should be very low computational cost.

Requirements

The algorithm needs to be

  • Computationally inexpensive - ideally we can run multiple channels simultaneously on an Arduino (or other low power microprocessor)
  • Robust to noise
  • Robust to a slowly-varying offset in the signal. For ideal sensor placement we should see 0V for no signal, but I have observed cases where we get a bias voltage.
  • Handle varying signal levels and other patient-to-patient differences.
  • Respect the kind of signal we need for the hand (e.g., no fast switching between 0 and 1).
  • Minimize false positives and false negatives.

Approach

For initial prototyping, I have written a simple Arduino sketch. This has a few benefits: it ensures we have a relatively computationally inexpensive algorithm, as the Arduino cannot handle much processing; it allows easy development and testing; and given that the sketch is more or less written in C, we should be able to easily transfer it to other microprocessors if necessary.

The Arduino EMG sketch is in the repository, alongside an open-source filtering package that you'll need to add as a library to the Arduino IDE.

The goal of the algorithm is to output a stable binary signal that is high when the muscle is being flexed, and low otherwise. The method for achieving this is described below.

Algorithm description

Here I'll step through the code and explain the functionality as we go.

/*
  InitialDetectorAlgorithm

  Development code for figuring out how to provide a robust signal
  from either EMG sensor

  For a detailed discussion of functionality and defining parameters, 
  see https://github.com/enable-medellin/El-Medallo-Bionic-Arm/wiki/Initial-EMG-Algorithm

  Bryn Davis

*/

#include <Filters.h>         // From https://github.com/JonHub/Filters

This is just initial comments and inclusion of the filter package mentioned above.

#define SensorInputPin A5    // input pin number

I have the signal coming in to A5. A0 is typically used but A5 is convenient for us as the FlexVolt shield can be put on top, and A5 is passed directly through to the Arduino. I.e., you don't need to remove the FlexVolt shield to use this EMG algorithm.

// Setup parameters
int sensor = 0;                   // 0 for Protesis Avanzada; 1 for OYMotion
int debug_signals = 1;            // 1 to show signals over serial

These are two switches that can be set to change the algorithm behavior. We use slightly different processing approaches between the Protesis Avanzadas sensor and the OYMotion sensor. The sensor switch makes the appropriate changes - set to 0 for the Protesis Avanzadas sensor and 1 for OYMotion. The debug_signals switch toggles whether various internal signals are output over serial. It can be very useful to visualize the signal, estimated background, etc. but the serial output does slow down the processing. I anticipate using debug_signals = 1 for development/debugging and debug_signals = 0 for implementation.

// Fixed parameters
float background_frequency = 0.2; // Change rate to be considered background (Hz)
float ceiling_frequency = 150;    // Highest expected frequency (Hz)
float fall_time = 1000;           // Signal must be low this long for 1 -> 0 (ms)

These are parameters that are common to both sensors. As part of the algorithm we estimate the "background" on the signal. Ideally this would be zero but we may get some residual signal when the muscle is relaxed. The approach taken to quantify this is to apply a (very) low pass filter, with the result being the background. background_frequency sets the cutoff frequency, in Hz, for this background-estimation filter.

Similarly, to reduce noise we can perform an additional low-pass filtering operation, with the cutoff frequency set by ceiling_frequency. This value should be above any expected usable signal band, but below the effective sampling rate (see discussion later). Optionally, this filtering can be disabled by setting ceiling_frequency to 0.

fall_time is a parameter that helps stop the detector output toggling too fast. Once a signal has been detected, the output stays high for this long after the EMG voltage has fallen. The idea is that this stops a brief gap in the EMG voltage from resulting in two separate output pulses. The parameter is specified in milliseconds and can reasonably be set to be on the same order as the time it takes to open or close the hand.

// Variable parameters we'll change in setup
float threshold;                     // Voltage above background to register signal
float rise_time;                     // Must see signal this long for 0 -> 1 (ms)
float background_timeout;            // Max time to not calculate background (ms)
float threshold_oy = .25;            
float rise_time_oy = 2;      
float background_timeout_oy = 5000;  
float threshold_pa = .5;         
float rise_time_pa = 100;    
float background_timeout_pa = 5000; 

This block initializes three parameters threshold, rise_time and background_timeout; and specifies values for each of the two sensor types. I.e., these are the parameters that differ between sensors. threshold is the minimum difference (in V) between the background and the signal that is classified as a potential muscle twitch.

rise_time is the minimum amount of time that a twitch signal must be observed to toggle the output to high - this is similar to fall_time but controls the low-to-high transition rather than the high-to-low.

'background_timeout` is a parameter used to overcome an undesirable steady state in the algorithm. If the output signal is high, then the background estimate is not altered. As a result if you have an inaccurate background, that results in a high output, then the background won't change and the signal will always stay high. This timeout parameter (specified in ms) gives the maximum amount of time that the background estimate will not be updated. After this time it is assumed the output is erroneously high, and we start updating the background estimate.

Differences in parameters between the two sensors are seen for threshold and rise_time. threshold captures differences in the voltage mapping (and potentially sensitivity) between the two devices. rise_time needs to be reduced for the OYMotion sensor as the signal is unrectified (crosses zero) and has higher frequency content that the Protesis Avanzadas sensor.

// Initialization
int state = 0;                 // 0 for no signal; 1 for signal
float background = 0;          // Tracks background level
bool high_now = false;         // Whether the instaneous signal is high
int last_low = 0;              // Time (ms) of last observed low
int last_high = 0;             // Time (ms) of last observed high
int last_background = 0;       // Time (ms) of contributing background
int current_time = 0;          // Tracking loop time (ms)
int previous_time = 0;         // Stores the previous time for rate calculations
float emg_signal;              // Current signal 

This block is just initialization of a number of variables that are convenient to make global.

  • state is the output of the algorithm and will be used to trigger the hand.
  • background is the current estimate of the signal background.
  • high_now is an instantaneous determination of whether we have a possible muscle twitch.
  • last_low and last_high record the most recent time we've seen each of these states in high_now. These are useful for evaluating against rise_time and fall_time.
  • last_background records the last time we updated the background estimate. This is useful for evaluating against background_timeout.
  • current_time is simply the system clock at the start of the current processing loop.
  • previous_time is from the previous loop and is used to quantify the system rate.
  • emg_signal is the current sensor voltage, after low-pass filtering.
// create a one pole filter to estimate background
FilterOnePole backgroundFilter(LOWPASS, background_frequency); 

// create a filter to remove high frequency noise  
FilterOnePole lowpassFilter(LOWPASS, ceiling_frequency); 

This block initializes two filters - one for background estimation and one for high-frequency noise rejection. Note that these are simple IIR (infinite impulse response) filters but they have the advantage that they do not require a fixed sample rate. Basically, we can just let the main processing loop run as fast as it can.

// the setup routine runs once when you press reset:
void setup() {
 
  // initialize serial communication at 19200 bits per second:
  Serial.begin(38400);

  // Initialize the on-board LED (will use it to show state)
  pinMode(LED_BUILTIN, OUTPUT);

  // Set sensor specific parameters (TODO - Figure out how to do this only once)
  if (sensor == 0){
    threshold = threshold_pa;
    rise_time = rise_time_pa; 
    background_timeout = background_timeout_pa;
  }
  else if (sensor == 1){
    threshold = threshold_oy;
    rise_time = rise_time_oy; 
    background_timeout = background_timeout_oy;
  }

}

This setup function is run once on system start and accomplishes three things: it opens a serial connection to the computer; sets up the on-board LED to display the binary output of the algorithm; and sets the appropriate parameters depending on the sensor type.

// the loop routine runs over and over
void loop() {
  
  // read the input:
  int sensorValue = analogRead(SensorInputPin);
  current_time = millis();

This is the start of the processing loop, reading of the sensor, and recording the current system time.

  // Convert the analog reading (which goes from 0 - 1023) to a voltage (0 - 5V):
  float voltage = sensorValue * (5.0 / 1023.0);

The Arduino maps the 0-5V input on to a 10-bit scale. For consistency, it's easiest to convert this back to the physical voltage.

  // do low pass filtering
  if (ceiling_frequency == 0){     // Do nothing
    emg_signal = voltage;
  }
  else {                           // Filter out high frequencies
    emg_signal = lowpassFilter.input(voltage);    
  }

This block is the low-pass noise rejection filter. Note that it can be turned off by setting ceiling_frequency = 0 above.

  // Do accounting based on whether we are exceeding threshold
  if (sensor == 0){
    high_now = (emg_signal - background) > threshold;
  }
  else if (sensor == 1){
    high_now = abs(emg_signal - background) > threshold;
  }

Here we are determining whether we are seeing a possible twitch signal. The main quantity of interest is the difference between the current signal and the estimated background (emg_signal - background). However, we need to treat the sensors slightly differently, as the Protesis Avanzadas sensor provides a rectified output. I.e., for the OYMotion sensor, a large positive or negative difference can indicate a muscle twitch, while for the Protesis Avanzadas device we expect only positive differences.

  if (high_now) {
    last_high = current_time;
  }
  else {
    last_low = current_time;
  }

This is just an update to when we last saw a particular state in high_now.

  // Determine the state 
  if (high_now) {
    if ((current_time - last_low) > rise_time) {
      state = 1;
    }
  }
  else {     // not high_now
    if ((current_time - last_high) > fall_time) {
      state = 0;
    }
  }

This block evaluates how our instantaneous signal has behaved over recent history, and determines whether the behavior is consistent with a high or low output. Specifically, if we've been observing a likely muscle twitch for more than rise_time, then the output is switched to high. And if we haven't seen a likely signal for more than fall_time, then the state can be set to low.

  // Track the background
  if ((state == 0) and not high_now){
    background = backgroundFilter.input(emg_signal);
    last_background = current_time;
    }

Here we track the estimated background using a low-pass filter, but only if we don't think a muscle twitch is present (in which case, the signal is not representative of the background).

  else if (current_time - last_background > background_timeout){
    background = backgroundFilter.input(emg_signal);      
  }

But if we haven't updated the background estimate in a long time, we go ahead and update it regardless of state. This prevents the lock-up condition described earlier.

  // Print out the signal values
  if (debug_signals == 1){
     Serial.print(emg_signal);
     Serial.print("   ");
     Serial.print(state);
     Serial.print("   ");
  // Serial.print(high_now);
  // Serial.print("   ");
     Serial.print(background);
     Serial.print("   ");
  }

This block outputs the most useful signals over serial. Visualization with the serial plotter is particularly informative. Note that high_now is commented out above, as it's generally a bit redundant when plotted with both emg_signal and state. However, if things are really misbehaving, it might be necessary to look at this signal too.

The image above shows a screenshot from the Arduino serial plotter for the Protesis Avanzadas sensor. Here the blue line is emg_signal, the red line is state, the green line is background, and the orange line is the sample rate in 100s of Hz (see below). This plot illustrates a number of features of the algorithm, e.g.; a sustained emg_signal is required to raise the output state to high; state remains high for a significant period after the signal drops; and that a relatively brief drop in won't change the state.

  // Track the speed (in hundreds of Hz to keep similar scale)
  float rate = 10. / (current_time - previous_time);
  previous_time = current_time;
  Serial.println(rate);

This block performs a rate calculation, so we can see how fast the sampling is running. The output is plotted in hundreds of Hz so it can be easily seen on the same scale as the debug signals above. For a single channel, we expect something on the order of 500-1000Hz when the debug signals aren't plotted, and more like 150Hz when they are. Note that because the times are recorded in ms, the rate output is very coarse. I guess we could keep track of time in us, but the timer overflows after only 70 minutes in this case. I think keeping a long overflow period is better than having fine detail on the rate output. Also, it seems like the sampling rate is fairly dependent on the serial baud rate, and so it's likely things will run faster in the final system, when we are not outputting over serial. It may be worth outputting on a digital Arduino pin instead, and measuring frequency with an oscilloscope.

  // Control the digital outputs
  if (state == 1){digitalWrite(LED_BUILTIN, HIGH);}
  else {digitalWrite(LED_BUILTIN, LOW);}
  
}

This algorithm finishes by writing the state to the on-board Arduino LED. This is useful for visualizing the signal (especially when not using debugging) but may need to be changed if we use a board without this LED.

Clone this wiki locally