Tx only needed oSoftserial lib for MIDI on T3.6 -

Status
Not open for further replies.

SteveBar

Well-known member
Tx only needed in Softserial lib for MIDI on T3.6 -

If I missed this info in another thread feel free to point to it, I’ve been browsing and reading for several hours today and haven’t come across these answers. But learned a ton of other stuff in the search! :)

I’m working on a MIDI router device that bridges several “5-pin DINs” (via serial UARTs) to the “USB device port” and the “USB host ports via 4 port hub”.

I was hoping to get some feedback on optimizing the softserial library when only MIDI messages are needed to be transmitted (Tx’ed). I edited the Softserial library removing as much RX code as possible, but still leaving return values as if the input buffer is empty. The program creates 8 softserial objects using the same Input pin and they seem to be working fine. FYI There are a total of 14 MIDI outputs, the first 6 of which are using UART serial ports.

Question: does each instantiated object create its own interrupt timer to manage the outbound pulse train? At what cost w.r.t. starving other interrupt threads? Maybe I’m even asking the wrong question... can somebody describe the theory of operation for the soft serial transmit, and what the pitfalls might be for running eight of them. The warnings are strong but a bit vague on the PJRC website on this matter.

Thanks in advance!
Steve
 
Last edited:
Here's the SoftwareSerial.cpp that I modified... all locations where code was commented out or added has the comment... "// added by SEB to remove RX delays"

Code:
/*
SoftwareSerial.cpp (formerly NewSoftSerial.cpp) - 
Multi-instance software serial library for Arduino/Wiring
-- Interrupt-driven receive and other improvements by ladyada
   (http://ladyada.net)
-- Tuning, circular buffer, derivation from class Print/Stream,
   multi-instance support, porting to 8MHz processors,
   various optimizations, PROGMEM delay tables, inverse logic and 
   direct port writing by Mikal Hart (http://www.arduiniana.org)
-- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
-- 20MHz processor support by Garrett Mace (http://www.macetech.com)
-- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)

This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.

This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA

The latest version of this library can always be found at
http://arduiniana.org.
*/

// When set, _DEBUG co-opts pins 11 and 13 for debugging with an
// oscilloscope or logic analyzer.  Beware: it also slightly modifies
// the bit times, so don't rely on it too much at high baud rates
#define _DEBUG 0
#define _DEBUG_PIN1 11
#define _DEBUG_PIN2 13
// 
// Includes
// 
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <Arduino.h>
#include <SoftwareSerial.h>


#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)

SoftwareSerial::SoftwareSerial(uint8_t rxPin, uint8_t txPin, bool inverse_logic /* = false */)
{
	buffer_overflow = false;
	if (rxPin == 0 && txPin == 1) {
		port = &Serial1;
		return;
	} else if (rxPin == 9 && txPin == 10) {
		port = &Serial2;
		return;
	} else if (rxPin == 7 && txPin == 8) {
		port = &Serial3;
		return;
	}
	port = NULL;
	pinMode(txPin, OUTPUT);
	pinMode(rxPin, INPUT_PULLUP);
	txpin = txPin;
	rxpin = rxPin;
	txreg = portOutputRegister(digitalPinToPort(txPin));
	rxreg = portInputRegister(digitalPinToPort(rxPin));
	cycles_per_bit = 0;
}

void SoftwareSerial::begin(unsigned long speed)
{
	if (port) {
		port->begin(speed);
	} else {
		cycles_per_bit = (uint32_t)(F_CPU + speed / 2) / speed;
		ARM_DEMCR |= ARM_DEMCR_TRCENA;
		ARM_DWT_CTRL |= ARM_DWT_CTRL_CYCCNTENA;
	}
}

void SoftwareSerial::end()
{
	if (port) {
		port->end();
		port = NULL;
	} else {
		pinMode(txpin, INPUT);
		pinMode(rxpin, INPUT);
	}
	cycles_per_bit = 0;
}

// The worst case expected length of any interrupt routines.  If an
// interrupt runs longer than this number of cycles, it can disrupt
// the transmit waveform.  Increasing this number causes SoftwareSerial
// to hog the CPU longer, delaying all interrupt response for other
// libraries, so this should be made as small as possible but still
// ensure accurate transmit waveforms.
#define WORST_INTERRUPT_CYCLES 360

static void wait_for_target(uint32_t begin, uint32_t target)
{
	if (target - (ARM_DWT_CYCCNT - begin) > WORST_INTERRUPT_CYCLES+20) {
		uint32_t pretarget = target - WORST_INTERRUPT_CYCLES;
		//digitalWriteFast(12, HIGH);
		interrupts();
		while (ARM_DWT_CYCCNT - begin < pretarget) ; // wait
		noInterrupts();
		//digitalWriteFast(12, LOW);
	}
	while (ARM_DWT_CYCCNT - begin < target) ; // wait
}

size_t SoftwareSerial::write(uint8_t b)
{
	elapsedMicros elapsed;
	uint32_t target;
	uint8_t mask;
	uint32_t begin_cycle;

	// use hardware serial, if possible
	if (port) return port->write(b);
	if (cycles_per_bit == 0) return 0;
	ARM_DEMCR |= ARM_DEMCR_TRCENA;
	ARM_DWT_CTRL |= ARM_DWT_CTRL_CYCCNTENA;
	// start bit
	target = cycles_per_bit;
	noInterrupts();
	begin_cycle = ARM_DWT_CYCCNT;
	*txreg = 0;
	wait_for_target(begin_cycle, target);
	// 8 data bits
	for (mask = 1; mask; mask <<= 1) {
		*txreg = (b & mask) ? 1 : 0;
		target += cycles_per_bit;
		wait_for_target(begin_cycle, target);
	}
	// stop bit
	*txreg = 1;
	interrupts();
	target += cycles_per_bit;
	while (ARM_DWT_CYCCNT - begin_cycle < target) ; // wait
	return 1;
}

void SoftwareSerial::flush()
{
	if (port) port->flush();
}

// TODO implement reception using pin change DMA capturing
// ARM_DWT_CYCCNT and the bitband mapped GPIO_PDIR register
// to a circular buffer (8 bytes per event... memory intensive)

int SoftwareSerial::available()
{
	if (port) return port->available();
	return 0;
}

int SoftwareSerial::peek()
{
	if (port) return port->peek();
	return -1;
}

int SoftwareSerial::read()
{
	if (port) return port->read();
	return -1;
}

#else

//
// Lookup table
//
typedef struct _DELAY_TABLE
{
  long baud;
  unsigned short rx_delay_centering;
  unsigned short rx_delay_intrabit;
  unsigned short rx_delay_stopbit;
  unsigned short tx_delay;
} DELAY_TABLE;

#if F_CPU == 16000000

static const DELAY_TABLE PROGMEM table[] = 
{
  //  baud    rxcenter   rxintra    rxstop    tx
  { 115200,   1,         17,        17,       12,    },
  { 57600,    10,        37,        37,       33,    },
  { 38400,    25,        57,        57,       54,    },
  { 31250,    31,        70,        70,       68,    },
  { 28800,    34,        77,        77,       74,    },
  { 19200,    54,        117,       117,      114,   },
  { 14400,    74,        156,       156,      153,   },
  { 9600,     114,       236,       236,      233,   },
  { 4800,     233,       474,       474,      471,   },
  { 2400,     471,       950,       950,      947,   },
  { 1200,     947,       1902,      1902,     1899,  },
  { 600,      1902,      3804,      3804,     3800,  },
  { 300,      3804,      7617,      7617,     7614,  },
};

const int XMIT_START_ADJUSTMENT = 5;

#elif F_CPU == 8000000

static const DELAY_TABLE table[] PROGMEM = 
{
  //  baud    rxcenter    rxintra    rxstop  tx
  { 115200,   1,          5,         5,      3,      },
  { 57600,    1,          15,        15,     13,     },
  { 38400,    2,          25,        26,     23,     },
  { 31250,    7,          32,        33,     29,     },
  { 28800,    11,         35,        35,     32,     },
  { 19200,    20,         55,        55,     52,     },
  { 14400,    30,         75,        75,     72,     },
  { 9600,     50,         114,       114,    112,    },
  { 4800,     110,        233,       233,    230,    },
  { 2400,     229,        472,       472,    469,    },
  { 1200,     467,        948,       948,    945,    },
  { 600,      948,        1895,      1895,   1890,   },
  { 300,      1895,       3805,      3805,   3802,   },
};

const int XMIT_START_ADJUSTMENT = 4;

#elif F_CPU == 20000000

// 20MHz support courtesy of the good people at macegr.com.
// Thanks, Garrett!

static const DELAY_TABLE PROGMEM table[] =
{
  //  baud    rxcenter    rxintra    rxstop  tx
  { 115200,   3,          21,        21,     18,     },
  { 57600,    20,         43,        43,     41,     },
  { 38400,    37,         73,        73,     70,     },
  { 31250,    45,         89,        89,     88,     },
  { 28800,    46,         98,        98,     95,     },
  { 19200,    71,         148,       148,    145,    },
  { 14400,    96,         197,       197,    194,    },
  { 9600,     146,        297,       297,    294,    },
  { 4800,     296,        595,       595,    592,    },
  { 2400,     592,        1189,      1189,   1186,   },
  { 1200,     1187,       2379,      2379,   2376,   },
  { 600,      2379,       4759,      4759,   4755,   },
  { 300,      4759,       9523,      9523,   9520,   },
};

const int XMIT_START_ADJUSTMENT = 6;

#else

#error This version of SoftwareSerial supports only 20, 16 and 8MHz processors

#endif

//
// Statics
//
SoftwareSerial *SoftwareSerial::active_object = 0;
char SoftwareSerial::_receive_buffer[_SS_MAX_RX_BUFF]; 
volatile uint8_t SoftwareSerial::_receive_buffer_tail = 0;
volatile uint8_t SoftwareSerial::_receive_buffer_head = 0;

//
// Debugging
//
// This function generates a brief pulse
// for debugging or measuring on an oscilloscope.
inline void DebugPulse(uint8_t pin, uint8_t count)
{
#if _DEBUG
  volatile uint8_t *pport = portOutputRegister(digitalPinToPort(pin));

  uint8_t val = *pport;
  while (count--)
  {
    *pport = val | digitalPinToBitMask(pin);
    *pport = val;
  }
#endif
}

//
// Private methods
//

/* static */ 
inline void SoftwareSerial::tunedDelay(uint16_t delay) { 
  uint8_t tmp=0;

  asm volatile("sbiw    %0, 0x01 \n\t"
    "ldi %1, 0xFF \n\t"
    "cpi %A0, 0xFF \n\t"
    "cpc %B0, %1 \n\t"
    "brne .-10 \n\t"
    : "+r" (delay), "+a" (tmp)
    : "0" (delay)
    );
}

// This function sets the current object as the "listening"
// one and returns true if it replaces another 
bool SoftwareSerial::listen()
{
  if (active_object != this)
  {
    _buffer_overflow = false;
    uint8_t oldSREG = SREG;
    cli();
    _receive_buffer_head = _receive_buffer_tail = 0;
    active_object = this;
    SREG = oldSREG;
    return true;
  }

  return false;
}

//
// The receive routine called by the interrupt handler
//
void SoftwareSerial::recv()
{
      return;  // added by SEB to remove RX delays
	  
 /*
#if GCC_VERSION < 40302
// Work-around for avr-gcc 4.3.0 OSX version bug
// Preserve the registers that the compiler misses
// (courtesy of Arduino forum user *etracer*)
  asm volatile(
    "push r18 \n\t"
    "push r19 \n\t"
    "push r20 \n\t"
    "push r21 \n\t"
    "push r22 \n\t"
    "push r23 \n\t"
    "push r26 \n\t"
    "push r27 \n\t"
    ::);
#endif  

  uint8_t d = 0;

  // If RX line is high, then we don't see any start bit
  // so interrupt is probably not for us
  if (_inverse_logic ? rx_pin_read() : !rx_pin_read())
  {
    // Wait approximately 1/2 of a bit width to "center" the sample
    tunedDelay(_rx_delay_centering);
    DebugPulse(_DEBUG_PIN2, 1);

    // Read each of the 8 bits
    for (uint8_t i=0x1; i; i <<= 1)
    {
      tunedDelay(_rx_delay_intrabit);
      DebugPulse(_DEBUG_PIN2, 1);
      uint8_t noti = ~i;
      if (rx_pin_read())
        d |= i;
      else // else clause added to ensure function timing is ~balanced
        d &= noti;
    }

    // skip the stop bit
    tunedDelay(_rx_delay_stopbit);
    DebugPulse(_DEBUG_PIN2, 1);

    if (_inverse_logic)
      d = ~d;

    // if buffer full, set the overflow flag and return
    if ((_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF != _receive_buffer_head) 
    {
      // save new data in buffer: tail points to where byte goes
      _receive_buffer[_receive_buffer_tail] = d; // save new byte
      _receive_buffer_tail = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
    } 
    else 
    {
#if _DEBUG // for scope: pulse pin as overflow indictator
      DebugPulse(_DEBUG_PIN1, 1);
#endif
      _buffer_overflow = true;
    }
  }

#if GCC_VERSION < 40302
// Work-around for avr-gcc 4.3.0 OSX version bug
// Restore the registers that the compiler misses
  asm volatile(
    "pop r27 \n\t"
    "pop r26 \n\t"
    "pop r23 \n\t"
    "pop r22 \n\t"
    "pop r21 \n\t"
    "pop r20 \n\t"
    "pop r19 \n\t"
    "pop r18 \n\t"
    ::);
#endif
*/
}

void SoftwareSerial::tx_pin_write(uint8_t pin_state)
{
  if (pin_state == LOW)
    *_transmitPortRegister &= ~_transmitBitMask;
  else
    *_transmitPortRegister |= _transmitBitMask;
}

uint8_t SoftwareSerial::rx_pin_read()
{
  return *_receivePortRegister & _receiveBitMask;
}

//
// Interrupt handling
//

/* static */
inline void SoftwareSerial::handle_interrupt()
{
  if (active_object)
  {
    // active_object->recv();
  }
}

#if defined(PCINT0_vect)
ISR(PCINT0_vect)
{
  // SoftwareSerial::handle_interrupt();  // added by SEB to remove RX delays
}
#endif

#if defined(PCINT1_vect)
ISR(PCINT1_vect)
{
  // SoftwareSerial::handle_interrupt();  // added by SEB to remove RX delays
}
#endif

#if defined(PCINT2_vect)
ISR(PCINT2_vect)
{
  // SoftwareSerial::handle_interrupt();  // added by SEB to remove RX delays
}
#endif

#if defined(PCINT3_vect)
ISR(PCINT3_vect)
{
  // SoftwareSerial::handle_interrupt();  // added by SEB to remove RX delays
}
#endif

//
// Constructor
//
SoftwareSerial::SoftwareSerial(uint8_t receivePin, uint8_t transmitPin, bool inverse_logic /* = false */) : 
  _rx_delay_centering(0),
  _rx_delay_intrabit(0),
  _rx_delay_stopbit(0),
  _tx_delay(0),
  _buffer_overflow(false),
  _inverse_logic(inverse_logic)
{
  setTX(transmitPin);
  setRX(receivePin);
}

//
// Destructor
//
SoftwareSerial::~SoftwareSerial()
{
  end();
}

void SoftwareSerial::setTX(uint8_t tx)
{
  pinMode(tx, OUTPUT);
  digitalWrite(tx, HIGH);
  _transmitBitMask = digitalPinToBitMask(tx);
  uint8_t port = digitalPinToPort(tx);
  _transmitPortRegister = portOutputRegister(port);
}

void SoftwareSerial::setRX(uint8_t rx)
{
  pinMode(rx, INPUT);
  if (!_inverse_logic)
    digitalWrite(rx, HIGH);  // pullup for normal logic!
  _receivePin = rx;
  _receiveBitMask = digitalPinToBitMask(rx);
  uint8_t port = digitalPinToPort(rx);
  _receivePortRegister = portInputRegister(port);
}

//
// Public methods
//

void SoftwareSerial::begin(long speed)
{
  _rx_delay_centering = _rx_delay_intrabit = _rx_delay_stopbit = _tx_delay = 0;

  for (unsigned i=0; i<sizeof(table)/sizeof(table[0]); ++i)
  {
    long baud = pgm_read_dword(&table[i].baud);
    if (baud == speed)
    {
      _rx_delay_centering = pgm_read_word(&table[i].rx_delay_centering);
      _rx_delay_intrabit = pgm_read_word(&table[i].rx_delay_intrabit);
      _rx_delay_stopbit = pgm_read_word(&table[i].rx_delay_stopbit);
      _tx_delay = pgm_read_word(&table[i].tx_delay);
      break;
    }
  }

  // Set up RX interrupts, but only if we have a valid RX baud rate
  
  /* // added by SEB to remove RX delays
  if (_rx_delay_stopbit)
  {
    if (digitalPinToPCICR(_receivePin))
    {
      *digitalPinToPCICR(_receivePin) |= _BV(digitalPinToPCICRbit(_receivePin));
      *digitalPinToPCMSK(_receivePin) |= _BV(digitalPinToPCMSKbit(_receivePin));
    }
    tunedDelay(_tx_delay); // if we were low this establishes the end
  }
  */

#if _DEBUG
  pinMode(_DEBUG_PIN1, OUTPUT);
  pinMode(_DEBUG_PIN2, OUTPUT);
#endif

  listen();
}

void SoftwareSerial::end()
{
  if (digitalPinToPCMSK(_receivePin))
    *digitalPinToPCMSK(_receivePin) &= ~_BV(digitalPinToPCMSKbit(_receivePin));
}


// Read data from buffer
int SoftwareSerial::read()
{
  return -1;  // added by SEB to remove RX delays
  
  /* // added by SEB to remove RX delays
  if (!isListening())
    return -1;

  // Empty buffer?
  if (_receive_buffer_head == _receive_buffer_tail)
    return -1;

  // Read from "head"
  uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
  _receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
  return d;
  */ 
}

int SoftwareSerial::available()
{
  return 0; // added by SEB to remove RX delays
  
  /*  // added by SEB to remove RX delays
  if (!isListening())
    return 0;

  return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
  */
}

size_t SoftwareSerial::write(uint8_t b)
{
  if (_tx_delay == 0) {
    setWriteError();
    return 0;
  }

  uint8_t oldSREG = SREG;
  cli();  // turn off interrupts for a clean txmit

  // Write the start bit
  tx_pin_write(_inverse_logic ? HIGH : LOW);
  tunedDelay(_tx_delay + XMIT_START_ADJUSTMENT);

  // Write each of the 8 bits
  if (_inverse_logic)
  {
    for (byte mask = 0x01; mask; mask <<= 1)
    {
      if (b & mask) // choose bit
        tx_pin_write(LOW); // send 1
      else
        tx_pin_write(HIGH); // send 0
    
      tunedDelay(_tx_delay);
    }

    tx_pin_write(LOW); // restore pin to natural state
  }
  else
  {
    for (byte mask = 0x01; mask; mask <<= 1)
    {
      if (b & mask) // choose bit
        tx_pin_write(HIGH); // send 1
      else
        tx_pin_write(LOW); // send 0
    
      tunedDelay(_tx_delay);
    }

    tx_pin_write(HIGH); // restore pin to natural state
  }

  SREG = oldSREG; // turn interrupts back on
  tunedDelay(_tx_delay);
  
  return 1;
}

void SoftwareSerial::flush()
{
  
  return // added by SEB to remove RX delays
  
  /*  // added by SEB to remove RX delays
  if (!isListening())
    return;

  uint8_t oldSREG = SREG;
  cli();
  _receive_buffer_head = _receive_buffer_tail = 0;
  SREG = oldSREG;
  */
}

int SoftwareSerial::peek()
{
  return -1;  // added by SEB to remove RX delays
  
  /*  // added by SEB to remove RX delays
  if (!isListening())
    return -1;

  // Empty buffer?
  if (_receive_buffer_head == _receive_buffer_tail)
    return -1;

  // Read from "head"
  return _receive_buffer[_receive_buffer_head];
  */
}

#endif
 
Last edited:
For instance functions "tx_pin_write" & "tunedDelay" are called bracketed by toggling all interrupts. Could "tunedDelay" be achieved by setting a high priority micro-sec timer to the pulse width needed and use the timer tick to return? Thus not blocking other code from running while clocking out pulses.

Steve
 
For instance functions "tx_pin_write" & "tunedDelay" are called bracketed by toggling all interrupts. Could "tunedDelay" be achieved by setting a high priority micro-sec timer to the pulse width needed and use the timer tick to return? Thus not blocking other code from running while clocking out pulses.

Steve

BTW given its MIDI at 31250 baud its fixed at a 32usec pulse
 
Can’t understand your over-complicated approach. The Teensy 3.6 has 6 hardware UARTs. Each of these might serve for a 5pin Midi port. No need to waste cpu cycles and ram for bit banging with a soft serial emulation.
 
Can’t understand your over-complicated approach. The Teensy 3.6 has 6 hardware UARTs. Each of these might serve for a 5pin Midi port. No need to waste cpu cycles and ram for bit banging with a soft serial emulation.

FYI There are a total of 14 MIDI outputs, the first 6 of which are using UART serial ports.

I need more than 6 outputs.
Steve
 
Sorry, didn‘t see that. Can hardly imagine a use case with the need of 14 Midi ports especially since midi allows theoretically daisy-chaining devices, concentrating or adding up several streams on one port.

I’m now very interested to read more about your project!
 
MIDI can be daisy-chained from device to device... but that can add latency especially with older devices. And tedious when re-configuring equipment. So spitting the MIDI and running cables in parallel is common.
Steve

MRTR Black Top Mount v5.jpg
...preliminary UI design
 
Last edited:
Pretty sure you're going to be very unhappy with the performance of software emulated serial. While you can transmit 1 MIDI port quite well that way, the problem is the interrupt disable behavior interferes with everything else, including all 6 hardware serial ports. It can also add significant latency on the USB communication too. When any of those 8 extra emulated ports is active, and especially if 2 or more are transmitting bytes, you're going to find the whole system suffers terribly.

To get 14 MIDI OUT ports, you really should use two more Teensy 3.6 boards. Connect a hub on the USB host port on your main Teensy 3.6, and then plug in both of those boards. When you want to send a message beyond the 6th port, transmit it on the USB host port to one of those 2 other Teensy 3.6 boards, and let them take care of actually sending it as serial. The USBHost_t36 library has an example that shows how to forward MIDI messages, which should give you most of the code you'll need.

Make sure you get a Multi-TT type hub. Those are more efficient than Single-TT types.

You may believe that extra USB communication sounds like a lot of overhead, but I'm confident you will find it performs *much* better than disabling interrupts when more than 1 of those 14 ports is active. The serial bit times are lengthy compared to moving data around with USB. Even just 1 MIDI message at 31250 takes the entire time for a full USB frame (8 micro-frames between the host port and hub) which can convey a tremendous number of USB messages. Structuring the project this way, with 3 Teensy 3.6 boards and an extra step of USB communication will add much less latency than what you'll suffer from even one of those 8 emulated serial channels blocking interrupts when you really need the system to be responsive for the other 13 channels.
 
Could the "tunedDelay" function in the Softwareserial lib be achieved by using a high priority 32 micro-sec interrupt timer, and not turning off interrupts?

Guess I’m asking for someone’s help... I know the theory a bit, but I’m not a low level skilled coder.

A Software Serial, TX only, for MIDI (31250 baud only) that bit bangs using a interrupt timer that supports multiple object instantiation. Could this work?

Steve
 
I doubt that this works for that number of parallel sending TXs. Then, the core disables interrupts, too, at various places.
Paul is right, the best, *reliable*, way is to use more Teensys.
 
Hm, on the other hand, If only 8x TX is needed you can write code to do it in sync- means toggle 8 TX pins instead of only one in your Softwareserial. In the T4 Beta thread there is an example for a efficient minimal code softwareserail ( don't have the link at hand) - that can be easily expanded to 8x digitalWriteFast. Might be worth a try.
 
Excuse if this is way off base... but if you're not processing the MIDI messages in any way that alters them; what about controlling a MUX with at Teensy to physically route signals?

Does anyone really have this many physical MIDI devices that need to be routed independantly?
 
Are all 14 incoming MIDI message streams arriving on a single 31250 baud input? Or are they coming in over 12 Mbit USB? Somehow I assumed USB was used, but now I'm not so sure. Much is a bit unclear here...
 
Are all 14 incoming MIDI message streams arriving on a single 31250 baud input? Or are they coming in over 12 Mbit USB? Somehow I assumed USB was used, but now I'm not so sure. Much is a bit unclear here...

Hi Paul/All,
Here are some more details... I have a prototype of this already built and running and about 60% of the code written. Below is the current input/output definitions of the MIDI router. Often MIDI routers have the same in number of inputs and outputs, this one does not. The front panel image is a few posts back.

Any input can be routed to one or more outputs. MIDI message filtering is also part of the feature set.

11 MIDI INPUTS ( 6x Serial (via UART), 4x USB Host, 1x USB device (w/16 Cables) )

19 MIDI OUTPUTS ( 6x Serial (via UART), 8x Soft-Serial, 4x USB Host, 1x USB device (w/16 Cables) )

Steve
 
Hi Frank,
Thanks for your feedback. In addition to using an interrupt timer I was planning to do all 8 outputs simultaneously in the same interrupt handler, as you mentioned. This will require only one 32 micro second timer for all eight outputs. Essentially doing all eight outputs in parallel and greatly reducing the number of timer interrupts for as many outputs.
Steve
 
If I did the calc right, a clock tic @240MHz ~4.2nano sec. so 30us = ~7200 ticks!
I think the ISR would need to inc a counter, test for empty buffer, test 8 on/off states and set 8 pin states to match.
Simple matter of programming... I’m sure I’m forgetting like 10 steps! :)
steve
 
Use FASTRUN on the function, so it's located in RAM with zero wait states. A function running that often would probably remain in the cache, but the cache on Teensy 3.6 is only 8K. Best to have such a speed critical ISR in RAM.

Of course, also make sure its interrupt priority is higher than all other interrupts. You can still disrupt your waveforms with any activity which temporarily disables interrupts (and many things do), but at least the nested interrupt priorities will give it the best chance of synthesizing those waveforms was well as possible.

The approach using 3 Teensy 3.6 boards would avoid those issues and likely perform better, so please keep that in mind if you run into trouble with the emulating serial ports.
 
Hi Frank,
Thanks for your feedback. In addition to using an interrupt timer I was planning to do all 8 outputs simultaneously in the same interrupt handler, as you mentioned. This will require only one 32 micro second timer for all eight outputs. Essentially doing all eight outputs in parallel and greatly reducing the number of timer interrupts for as many outputs.
Steve

I suggest you just write the low level code for this approach and forget about modifying softwareserial. The problem with softwareserial is that it is coded to send bytes, meaning that it blocks until the entire byte has been sent. With that approach, just one busy serial stream will consume all the processing power available.

You need to think in terms of sending one bit ( or 8 in parallel ) and returning from the interrupt. You can add 8 tx fifo's to make the higher level interface to your software serial simple and non-blocking.
 
MIDI Bit-Bang via 32usec Interrupt timer on T3.6

Here's my stab at writing the code. I love any feedback, suggestions, comments...

Theory of operation:
  1. setup 32usec interrupt timer at high priority to callback bit-bang function once per "tic"
  2. convert an inbound MIDI msg stream into a bit stream with start/stop bits etc... (manually done for this example)
  3. on int "tic" set digital pin based on buffer position

This version bit-bangs 1 output (Digital Pin 36) with a pre-configured MIDI message: Note On, Ch1, Note C4, Vel 127.
A 64 bit buffer is used, the message takes 30 bits, the remainder of the buffer are padded with zeros.
The buffer is sent repeatedly.

The interrupt timer is set to 32usec. this is the calc'ed & confirmed* pulse width per bit @ 31250 BAUD (10bits/byte) *MIDI association web site
I tried a small range of pulse width timings ~27-40 usec, with no better (but different message) result.
The interrupt priority 35 is used, below is a list of the other libs and their associated priorities that I put together from various post on this forum.
I tried it at priority 10 with no change observed.

Teensy Libs Timer Priorities...
TEENSY USB MIDI Driver XXXTimer.priority(112);
TEENSY Serial Driver XXXTimer.priority(64);
MIDI-BIT-BANG XXXTimer.priority(35); <----
TEENSY 'Sys Tick' Driver XXXTimer.priority(32);

I don't have a scope, but will have access to one in the next day or two.
Below is the MIDI-Ox input, does not match the sent message. In fact it's not reporting a 3 byte message being received

MIDI-OX input...
TIMESTAMP IN PORT STATUS DATA1 DATA2 CHAN NOTE EVENT
000B88FE 4- -- D8 7B -- 9 --- Channel Aft

Raw BIN = 0 1101 1000 1 0 0111 1011 1 = 0D81 07B1

Out vs In (bit order reversed) - NO MATCH at any position
RAW OUTPUT: 1111111100100111100010000100100000000000000000000000000000000000
MIDI-OX IN: 11101111001000110110

Code:
// ==================== Soft MIDI Tx ======================
      
    #define MAX_BITS 64
    #define TX_PIN   36
    
    volatile uint8_t gTxReadHead = 0;   // location of head to "bang-out" a bit from ring buffer
        
    // NoteOn(0x90) + Ch1(0x00), Note C4(0x3C), Vel127(0x7F) => 0 1001 0000 1 - 0 0011 1100 1 - 0 0111 1111 1;
    uint64_t msgNoteOn = 0b1111111100100111100010000100100000000000000000000000000000000000;  // reverse order, padded w/ 0's

    // Setup bit-bang 32usec timer tic (31250 BAUD)
    IntervalTimer sMIDITx_Timer;


// ========================================================

void BitBangPin() {   // called from interrupt timer

      boolean theBit;
          
      gTxReadHead = (gTxReadHead+1) % MAX_BITS;      // inc the "Read Head" of the buffer with wrapping
      theBit = !(1 & (msgNoteOn >> gTxReadHead));    // 
      digitalWriteFast(TX_PIN, theBit);              // write the bit to the pin from the buff location of the "read head"
      
      //Serial.println(String(theBit) + " <-" + gTxReadHead);  // make timer val 32000 to slow debug output
    
  
} // end fcn _SetPins

// ========================================================
    
void setup() {
  
   pinMode(TX_PIN, OUTPUT);
 
   //setup up Interrupt Timer     
   sMIDITx_Timer.priority(35);                // 35 = very high priority 
   
   // make timer val 32000 for debug output
   sMIDITx_Timer.begin(BitBangPin, 32);       // 32 usec == 31250 BAUD for MIDI

   Serial.println("MIDI Bit Bang running...");
}

// ========================================================

void loop() {
  
  // nothing in loop - fcn BitBangPins called from timer

}
 
I don't have a scope, but will have access to one in the next day or two.

I ran your code on a Teensy 3.6. Here's what my oscilloscope sees.

file.png

Here's a zoom in to just 1 frame of the data, with a custom time scale of 128 us/div so each bit is exactly 1/4th of a division on the screen.

file2.png
 
Thanks Paul...
I modified the image and super imposed the 0/1 stream... looks like the right bits are getting thru. I'll double check my "format" of the MIDI bit stream.
timingPJRC1.jpg
 
Status
Not open for further replies.
Back
Top