Return to Robotics Tutorials
ATtiny SPI slave code
This is Part 2 of a series describing how to use a Remote Control (RC) transmitter to drive a robot using an Arduino / ATtiny SPI slave. If you haven't already read it, please see Part 1 for the background material.
Table of Contents
- Part 1: Overview of RC Receiver to SPI interface
- Part 2: SPI slave code for ATtiny/Arduino
- ATtiny SPI slave C code
- Bus Pirate SPI master
- Raspberry Pi SPI master C code - Part 3: SPI slave data corruption
ATtiny SPI Slave Code
The following section details a few of the important details in writing C code for a SPI slave. A full program download is available at the end. The C code for the SPI slave was intended to work on an ATtiny167 microcontroller (used in a Digispark Pro), however it should also run on other ATtiny / ATmega / Arduino microcontrollers with small modifications.
Note that a number of #define statements have been made in the code to help improve readability and ease of configuration. Therefore, some of the code snippets below won't work until these definitions have been made (eg. PCINT_0_CH5). Please refer to the full code listing to see how these have been defined.
Portions of this same SPI slave code was also used in a UART-to-SPI bridge I wrote to add a SPI interface for a GPS.
Configure pins for SPI slave
Set up the pins for the SPI slave interface, and start with the SPI slave unselected (MISO is set to be an input):
// SPI pin definitions #define PIN_MOSI 10 // MOSI / PA4 #define PIN_MISO 8 // MISO / PA2 #define PIN_SCK 11 // SCK / PA5 #define PIN_CS 12 // SSb / PA6 / PCINT6 (ISR PCINT0) ... pinMode(PIN_MISO, INPUT); pinMode(PIN_MOSI, INPUT); pinMode(PIN_SCK, INPUT); pinMode(PIN_SS, INPUT);
Now that we've initialized the ports for the SPI interface, we need to enable it. This involves enabling the hardware SPI interface and then also enabling the SPI interrupt (SPI Transaction Complete ISR):
SPCR |= (1 << SPE) | (1 << SPIE);
Configure pulse monitoring
We then have to enable the pin change interrupts so that we can monitor the PWM pulses on each of the pins. The following code sets which pins will trigger a Pin Change event interrupt, and then enables each of these interrupts (PCIE0 and PCIE1).
PCMSK0 |= (1 << PCINT_0_CH5) | (1 << PCINT_0_CH6) | (1 << PCINT_0_SS); PCMSK1 |= (1 << PCINT_1_CH1) | (1 << PCINT_1_CH2) | (1 << PCINT_1_CH3) | (1 << PCINT_1_CH4); PCICR |= (1<<PCIE0) | (1<<PCIE1);
Create a SPI Transaction ISR
When using a hardware SPI slave, we need to write some code that handles the byte read/write actions during a SPI transaction. The hardware handles the individual bit transfers, but we must still handle the bytes. This is done in the SPI Transaction Complete ISR (interrupt service routine). Every time 8 bits have been transferred to/from the interface, the SPI_STC_vect ISR is called.
This is the most important section of code as it implements the SPI transaction protocol (ie. how reads and writes are signaled, the latching of incoming data from MOSI and the generation of read data from the slave via MISO). It is also very time sensitive as the master (eg. a Raspberry Pi) is generating the clock pulses that the slave must respond to.
ISR(SPI_STC_vect) { // Fetch the incoming data byte from the SPI Data Register nBufDat = SPDR; if (m_nXferCycle == 0) { // COMMAND cycle // Latch command nRegCmd = nBufDat; // Decode command m_nRegAddr = (nRegCmd & 0x0F); // Define 16 addresses / registers m_bRegRWb = (nRegCmd & 0xC0) >> 6; } else if (m_nXferCycle == 1) { // DATA cycle // Latch data if (m_bRegRWb == 0) { // Write command: Latch write data m_anRegArray[m_nRegAddr] = nBufDat; } else { // Read command: nothing to latch } } else if (m_nXferCycle == 2) { // DATA cycle #2 if (m_bRegRWb == 0) { // Write command: Latch write data m_anRegArray[m_nRegAddr+1] = nBufDat; } }
Now that we've captured the input (from MOSI), we need to define the output data (to MISO).
// ---------------------------------- // Setup output for next cycle // ---------------------------------- m_nXferCycle++; // If we are still the selected slave, then proceed to // define our outputs. Otherwise, we can ignore this // request. if (m_bSlaveSelected) { if (m_nXferCycle == 1) { // DATA cycle #1 // We only need to drive SPDR with valid data on a read // but for consistency, always return the current register value SPDR = m_anRegArray[m_nRegAddr]; } else if (m_nXferCycle == 2) { // DATA cycle #2 // For a 16-bit read, we advance the register address SPDR = m_anRegArray[m_nRegAddr+1]; } } else { // We are not selected for next cycle // The pin change int on SSb will be responsible // for tristating the MISO pin so that other slaves // can respond if they are selected. }
Create a Pin Change event ISR
In order to monitor the RC receiver's PWM signals, we need to detect transitions on each of the pins associated with the RC receiver channels. By enabling the Pin Change interrupts, we will be notified any time that either a rising or falling edge occurs on each non-masked pin.
However, this is complicated somewhat in the ATtiny / Arduino by the fact that multiple pins are monitored by the same interrupt / ISR. This means that a change to one or more pins may result in the same Pin Change ISR being called. Therefore, we need to determine which pin changed when we enter the ISR. The easiest way to do this is to compare the old pin values against the current pin values. For all differences, the associated pin is handled.
In the example below, Pin Change interrupt ISR #0 is associated with 3 "pins":
- SPI SSb
- RC Receiver Channel 5
- RC Receiver Channel 6
// Pin Change interrupt #0 ISR // // This ISR is responsible for monitoring the pins // associated with I/O bank 0. ISR(PCINT0_vect) { // Latch the current pin values and deltas uint8_t nPinValCur = PINA; uint8_t nPinValChg = nPinValCur ^ m_nPinALast; // Latch the current timestamp uint16_t nCurTimeUs = micros(); // ------------------------------------ // Handler for SSb if (nPinValChg & (1 << PORT_A_SS)) { if (nPinValCur & (1 << PORT_A_SS)) { // rising edge // SSb rising edge = deassertion // - We are not currently selected // - Release the bus DDR_MISO_PORT &= ~(1 << DDR_MISO_FIELD); // pinMode(PIN_MISO,INPUT) m_bSlaveSelected = false; } else { // SSb falling edge = assertion // - We weren't selected before, but now are // - Take ownership over the bus DDR_MISO_PORT |= (1 << DDR_MISO_FIELD); // pinMode(PIN_MISO,OUTPUT) // - Reset the transaction cycle m_nXferCycle = 0; m_bSlaveSelected = true; } } // ------------------------------------ // Handler for CH5 if (nPinValChg & (1 << PORT_A_CH5)) { if (nPinValCur & (1 << PORT_A_CH5)) { // rising edge m_nPinRiseTimeUs[IND_CH5] = nCurTimeUs; } else { // falling edge m_anPulseUs[IND_CH5] = nCurTimeUs-m_nPinRiseTimeUs[IND_CH5]; m_nPulsesNew |= (1<<IND_CH5); // Indicate a new pulse } } // ------------------------------------ // Handler for CH6 if (nPinValChg & (1 << PORT_A_CH6)) { if (nPinValCur & (1 << PORT_A_CH6)) { // rising edge m_nPinRiseTimeUs[IND_CH6] = nCurTimeUs; } else { // falling edge m_anPulseUs[IND_CH6] = nCurTimeUs-m_nPinRiseTimeUs[IND_CH6]; m_nPulsesNew |= (1<<IND_CH6); // Indicate a new pulse } } // ------------------------------------ // Cleanup // - Save the latest pin state m_nPinALast = nPinValCur; }
Detect Transmitter loss with Watchdog
It is essential that one finds a way to determine if the link to the transmitter is functional. If the transmitter is turned off, or it goes out of range from the receiver, we must ensure that the microcontroller takes appropriate action (eg. failsafe idle throttle, return to GPS coordinates, etc.). Please see more details of the transmitter loss detection / failsafe.
In the SPI slave code, we monitor the pulses and record the timestamp (in milliseconds) of the last pulse received per channel. The main loop is responsible for calculating the duration from the last timestamp to the current time and determining if we have exceeded the pulse timeout threshold. If we exceed the pulse timeout threshold on one or more of the critical channels, we raise the transmitter-loss flag (m_bTransmitterFail).
One might wonder why the watchdog timer function isn't done in the pin change interrupt ISR where we latch the pulse event in microseconds. There are a few reasons:
- We need to keep non-essential code out of the ISR. It is sufficient to check on the watchdog status periodically in the main loop.
- The microsecond counters in the ISR provide too much resolution versus the watchdog timeout. Since the microsecond counter rolls over frequently, we would have to manage this rollover in the watchdog code. Using the milliseconds counter doesn't have the same degree of problem.
uint16_t nPulseUsWidth; uint16_t nTimeMsCur; uint16_t nTimeMsElapsed; // Watchdog detector for (int nChan=0;nChan<NUM_CHAN;nChan++) { nTimeMsCur = millis(); if (m_nPulsesNew & (1<<nChan)) { // New pulse detected in ISR // Kick the watchdog m_nPinKickTimeMs[nChan] = nTimeMsCur; // Clear the timeout flag (if any) m_nPulsesTimeout &= ~(1<<nChan); // Reset the pulse detect m_nPulsesNew &= ~(1<<nChan); } else { // No new pulse, so check watchdog limit nTimeMsElapsed = nTimeMsCur-m_nPinKickTimeMs[nChan]; if (nTimeMsElapsed > PULSE_TIMEOUT) { // Set the timeout flag m_nPulsesTimeout |= (1<<nChan); } } } // Watchdog timeout -> Transmitter loss: // // If the RC transmitter is turned off (but the RC receiver // is still powered up), then most channels will not contain // pulses. However, some receivers (such as the Turnigy 9XCH8v2) // will still output a stream of pulses on one or more channels. // Therefore, the watchdog must only monitor certain channels // for inactivity. // - Only look at pulse train from CH1 & CH2 // - Note that Turnigy 9X8Cv2 seems to output very slow pulses // on CH4 & CH5 during transmitter loss. m_bTransmitterFail = 0; if (m_nPulsesTimeout & ( (1<<IND_CH1) | (1<<IND_CH2) ) ) { m_bTransmitterFail = 1; }
Store the pulse widths into SPI registers
Finally, we need to save the latest measured pulse widths into registers that can be accessed from the SPI hardware.
// Store the pulses into the registers for (int nChan=0;nChan<NUM_CHAN;nChan++) { // Disable ints for 16b coherency cli(); nPulseUsWidth = m_anPulseUs[nChan]; sei(); // Just report last saved pulse width. If there is a transmitter // fail, then the status flag can be used as a failsafe. m_anRegArray[REGBASE_CHAN+(nChan*REGS_PER_CHAN)+REG_PART_H] = nPulseUsWidth/256; m_anRegArray[REGBASE_CHAN+(nChan*REGS_PER_CHAN)+REG_PART_L] = nPulseUsWidth%256; } // nChan
Full C Code Download
The full C code for Arduino / ATtiny will be available for download shortly...
Optimizations: PORT Data Registers vs digitalWrite() / pinMode()
In some cases, it may be better to use the direct PORTxn hardware registers (eg. PORTA, PORTB) instead of calls to digitalWrite(). The reason for this is performance. If you examine the assembly code output for digitalWrite(), you will see a significant amount of overhead. If you are confident that a pin is only used as a simple digital IO (ie. not PWM, etc.) and you don't mind working out the pin mapping manually, then you may be able to get away without the extra overhead of the digitalWrite() / digitalRead() calls. This is particularly important in ISRs where you need to keep execution cycles to a minimum.
Here are some examples of optimizations that can be made:
Unoptimized Call | Optimized Code |
---|---|
digitalWrite(1,HIGH) | PORTB |= (1<<PORTB1) |
digitalWrite(1,LOW) | PORTB &= ~(1<<PORTB1) |
pinMode(8,OUTPUT) | DDRA |= (1<<DDA2) |
pinMode(8,INPUT) | DDRA &= ~(1<<DDA2) |
Testing with Raspberry Pi SPI Master Code
To be posted soon...
Testing with Bus Pirate SPI Master
The Bus Pirate is a versatile tool that can be used to test the SPI interface as a SPI master without writing any code. After connecting the 4 SPI pins, power and ground, we are ready to test the SPI slave on the ATtiny.
![]() |
Bus Pirate v3.5 connections for SPI |
---|
Configuring Bus Pirate for SPI
The following command sequence will configure the Bus Pirate to be a SPI master at 30kHz and a 3.3v signaling level:
HiZ>m 1. HiZ 2. 1-WIRE 3. UART 4. I2C 5. SPI 6. 2WIRE 7. 3WIRE 8. LCD 9. DIO x. exit(without change) (1)>5 Set speed: 1. 30KHz 2. 125KHz 3. 250KHz 4. 1MHz (1)>1 Clock polarity: 1. Idle low *default 2. Idle high (1)>1 Output clock edge: 1. Idle to active 2. Active to idle *default (2)>2 Input sample phase: 1. Middle *default 2. End (1)>1 CS: 1. CS 2. /CS *default (2)>2 Select output type: 1. Open drain (H=Hi-Z, L=GND) 2. Normal (H=3.3V, L=GND) (1)>2
Now that we've configured the SPI interface, we need to power up the ATtiny slave device. If you are using the Bus Pirate to power the device, then you need to use the "W" command to turn on the power supply. If you need to power it at 5v, then the Bus Pirate VPU pin needs to be connected to the Bus Pirate +5V pin and the output type needs to be set to "Open drain" in the config above. Enabling the power supply output is done with the "W" command as shown here:
Ready SPI>W Power supplies ON
After powering up the device, we can start issuing SPI transactions. There are a few ways to issue write / read transactions, but I found the most straightforward was to have the Bus Pirate report out both the incoming and outgoing bytes for every transfer in the transaction. Note that I use a "{" to start the transaction and a "]" to close the transaction.
In the example SPI slave code, a read transaction is signaled by a logic 1 in bit [6] of the first byte (ie. binary 8'b0100AAAA, where AAAA is the 4-bit register address).
SPI>{0x42 0x00 0x00] /CS ENABLED WRITE: 0x42 READ: 0xFF WRITE: 0x00 READ: 0x12 WRITE: 0x00 READ: 0x34 /CS DISABLED |
Bus Pirate SPI read transaction: 16-bit from address 0x02 |
---|
The SPI protocol is very open-ended, so the definition of read vs write and register addressing is left up to the particular SPI slave implementation. However, in the context of the SPI protocol written in the SPI slave code above, these commands will issue a 16-bit read to register 0x02. The 16-bit read data returned is 0x1234.
In the example SPI slave code, a write transaction is signaled by a logic 0 in bit [6] of the first byte (ie. binary 8'b0000AAAA, where AAAA is the 4-bit register address).
Therefore, sending 0x02 will perform a write transaction to register 0x02.
SPI>{0x02 0x55 0xAA] /CS ENABLED WRITE: 0x02 READ: 0xFF WRITE: 0x55 READ: 0x12 WRITE: 0xAA READ: 0x34 /CS DISABLED |
Bus Pirate SPI write transaction: 16-bit to address 0x02 |
---|
When performing a write transaction, the master can ignore the returned data (ie. READ:) in each of the transfers. Typically a SPI slave will return dummy data (eg. 0x00) or the current value of the register (before the write), eg. 0x1234.
SPI Slave Data Corruption
Once you have your ATtiny / Arduino SPI slave code working, you may start to encounter unexpected errors during reads and writes. Please see the next article: SPI Slave Data Corruption for more details.
Reader's Comments:
Please leave your comments or suggestions below!or something cut down to only 2 channels to help wrap my head around whats going on
none of these are defined in AVR studio
If it's helpful, I could probably post some of my complete code examples on GitHub as that'll probably be easier for readers to use.