SuperHouse / esp-open-rtos

Open source FreeRTOS-based ESP8266 software framework
BSD 3-Clause "New" or "Revised" License
1.52k stars 491 forks source link

i2c + ATTiny85 communication failure: Arbitration error #611

Open oschreibke opened 6 years ago

oschreibke commented 6 years ago

I'm trying to connect an ESP8266 to ATTiny85 development boards. The ATTiny does not have built in I2C support, so I'm using the tinywireS arduino library.

The hardware I built works for an Arduino sketch with the Wire library, and also a LUA program, but the ESP Open RTOS version fails. All three programs have similar functionality: Scan the i2c bus for devices, then issue commands to have the ATTinys position their attached servo.

In the RTOS version: scanning for the devices works, but sending commands doesn't. If I enable the debugging (I2C_DEBUG true), the program reports an Arbitration error on the write command. The behaviour seems similar to that reported in issue #429. The last commit on the esp-open-rtos library which I cloned a few days ago was 0fa4213577c7e5b82d51c46a80bd4d89fe02c5de.

Am I doing something stupid, or is this another manifestation of the timing difficulties in the I2C library?

Messages from the esp Open RTOS program:

 Scanning the i2c bus
 I2C: Bus 0 Write Error
 .. repeated
 I2C: Bus 0 Write Error
 Found i2c device at address 10
 Found i2c device at address 11
 I2C: Bus 0 Write Error
 .. repeated
 I2C: Bus 0 Write Error
 start_ServoController reinit the bus after scanning
 Getting response from 10
 I2C: Read Error
 I2C: arbitration lost in i2c_stop from bus 0 
 Call to i2c_slave_read(10, null, status, 1) failed, returned -5
 I2C: arbitration lost in i2c_start from bus 0
 I2C: arbitration lost in i2c_write_bit from bus 0
 I2C: arbitration lost in i2c_write_bit from bus 0
 I2C: Read Error
 Call to i2c_slave_read(10, null, angle, 1) failed, returned -5
 Received status 0, value 0, from slave 10.
 Terminating task 'start_ServoController' (me)

The relevant ESP Open RTOS code:

// ServoController.h

#ifndef OSC_SERVOCONTROLLER_H
#define OSC_SERVOCONTROLLER_H

//#include <timers.h>

// #ifndef ServoInfo
typedef struct ServoInfo {
    uint8_t iicAddress;
    bool moving;
    bool on;
    uint8_t onAngle;
    uint8_t offAngle;
    uint8_t status;
    uint8_t angle;
    uint16_t movementDelay;
} ServoInfo;
// #endif

void ServoController_task(void *pvParameters);
void MoveServo(uint8_t slaveAddress, uint8_t angle);
bool GetSlaveResponse(struct ServoInfo *slaveInfo);
void start_ServoController(void);

#endif
// ServoController.c

#include <stdbool.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h>

#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"

#include <i2c/i2c.h>
//#include "i2c.h"

//#ifndef ServoInfo
//typedef struct ServoInfo {
//uint8_t iicAddress;
//bool moving;
//bool on;
//uint8_t onAngle;
//uint8_t offAngle;
//uint8_t status;
//uint8_t angle;
//uint16_t movementDelay;
//} ServoInfo;
//#endif

#include "ServoController.h"

#define SCL_PIN  5
#define SDA_PIN  4

#define IICBUS 0

#define SLAVE1_ADDRESS 0x10
#define SLAVE2_ADDRESS 0x11

#define SECOND (1000 / portTICK_PERIOD_MS)

SemaphoreHandle_t xSemaphore = NULL;

struct ServoInfo servoInfo[2] = {{SLAVE1_ADDRESS, false, false, 45, 135, 0, 0, 10 * 1000},
    {SLAVE2_ADDRESS, false, false, 40, 140, 0, 0, 10 * 1000}
};

bool GetSlaveResponse(struct ServoInfo *slaveInfo) {
    //char c;

    //uint8_t tmp = slaveInfo->iicAddress;

    ////Serial.printf("Wire.requestFrom(%x);\r\n", tmp);

    //Wire.requestFrom(tmp, (uint8_t) 2);    // request 2 bytes from slave device

    //// wait for (at least) two bytes to arrive
    //while (Wire.available() < 2) {
    //yield();
    //};

    //slaveInfo->status = (uint8_t) Wire.read();  // receive a byte as character
    //slaveInfo->angle = (uint8_t) Wire.read();  // receive a byte as character

    bool status = true;
    uint8_t slaveStatus = slaveInfo->status;
    uint8_t slaveAngle = slaveInfo->angle;

    if( xSemaphoreTake( xSemaphore, portMAX_DELAY ) == pdTRUE ) {

        int rc = i2c_slave_read(IICBUS, slaveInfo->iicAddress, NULL, &slaveStatus, sizeof(slaveStatus));
        if (rc == 0) {
            slaveInfo->status = slaveStatus;
        } else {
            printf("Call to i2c_slave_read(%x, null, status, 1) failed, returned %d\n", slaveInfo->iicAddress, rc);
            status = false;
        }

        rc = i2c_slave_read(IICBUS, slaveInfo->iicAddress, NULL, &slaveAngle, sizeof(slaveAngle));
        if (rc == 0) {
            slaveInfo->angle = slaveAngle;
        } else {
            printf("Call to i2c_slave_read(%x, null, angle, 1) failed, returned %d\n", slaveInfo->iicAddress, rc);
            status = false;
        }

        xSemaphoreGive( xSemaphore );
    }

    printf("Received status %u, value %u, from slave %x.\r\n", slaveInfo->status, slaveInfo->angle, slaveInfo->iicAddress);

    return status;
}

void MoveServo(uint8_t slaveAddress, uint8_t angle) {
    //Wire.beginTransmission(slaveAddress); // transmit to device #8
    //Wire.write(angle);              // sends one byte
    //if (Wire.endTransmission() == 0) {    // stop transmitting

    if( xSemaphoreTake( xSemaphore, portMAX_DELAY ) == pdTRUE ) {

        int rc = i2c_slave_write(IICBUS, slaveAddress, NULL, &angle, sizeof(uint8_t));
        if (rc == 0) {
            printf("Sent %u to slave %x.\r\n", angle, slaveAddress);
        } else {
            printf("Send to slave %x failed, returned %d.\r\n", slaveAddress, rc);
        }
        xSemaphoreGive( xSemaphore );
    }
}

void ServoController_task(void * pSlaveInfo) {
    for(;;) {
        struct ServoInfo * slaveInfo = (struct ServoInfo *) pSlaveInfo;
        GetSlaveResponse(slaveInfo);

        // have we reached the end of travel?
        slaveInfo->moving = !( slaveInfo->angle == slaveInfo->onAngle || slaveInfo->angle == slaveInfo->offAngle );
        if ( !slaveInfo->moving ) {
            // wait for the delay to elapse
            //if (milliTick) {
            if (!--slaveInfo->movementDelay) {
                slaveInfo->movementDelay = 10 * 1000;
                //Serial.print("servoOn: "); Serial.println(servoOn);
                slaveInfo->on = ! slaveInfo->on;
                MoveServo(slaveInfo->iicAddress, (uint8_t)(slaveInfo->on ? slaveInfo->onAngle : slaveInfo->offAngle));
                //Serial.print("servoOn: "); Serial.println(servoOn);
            }
            //}
        }
        vTaskDelay(1/portTICK_PERIOD_MS);
    }
}

void start_ServoController(void) {
    bool initOK = true;

    xSemaphore = xSemaphoreCreateMutex();

    printf("%s: calling i2cInit\n", __func__);
    printf("SCL_PIN: %d, SDA_PIN: %d\n", SCL_PIN, SDA_PIN);

    i2c_init(IICBUS, SCL_PIN, SDA_PIN, I2C_FREQ_100K);

    printf("%s: waiting 10 sec for slaves to initialise.\n", __func__);
    vTaskDelay(10 * SECOND); // give the slaves time to initialise

    printf("Scanning the i2c bus\n");
    uint8_t addr;
    for (addr = 0x08; addr < 128; addr++) {
        uint8_t dummy = 90;
        // Write data to slave
        if (i2c_slave_write(IICBUS, addr, NULL, &dummy, sizeof(dummy))==0) {
            printf("Found i2c device at address %02X\n", addr);
        }
    }

    printf("%s reinit the bus after scanning\n", __func__);
    i2c_init(IICBUS, SCL_PIN, SDA_PIN, I2C_FREQ_100K);

    printf("Getting response from %x\r\n", servoInfo[0].iicAddress);
    initOK = initOK & GetSlaveResponse(&servoInfo[0]);

    //printf("Getting response from %x\r\n", servoInfo[1].iicAddress);
    //initOK = initOK & GetSlaveResponse(&servoInfo[1]);

    if (initOK) {

        MoveServo(servoInfo[0].iicAddress, (uint8_t)(servoInfo[0].on ? servoInfo[0].onAngle : servoInfo[0].offAngle));
        //MoveServo(servoInfo[1].iicAddress, (uint8_t)(servoInfo[1].on ? servoInfo[1].onAngle : servoInfo[1].offAngle));

        vTaskDelay(10 * SECOND); // give the slaves time to position

        printf("setup() complete.\n");

        printf("create ServoController_tasks\n");
        // Create user interface task
        xTaskCreate(ServoController_task, "ServoController_task_1", 256, (void *)&servoInfo[0], 2, NULL);
        //xTaskCreate(ServoController_task, "ServoController_task_2", 256, (void *)&servoInfo[1], 2, NULL);
    }

    printf("Terminating task 'start_ServoController' (me)\n");
    vTaskDelete(NULL);
}

The Arduino code:


/*
 * ESP8266_iic_ServoController.ino
 *
 * Copyright 2017 Otto Schreibke <oschreibke@gmail.com>
 *
 * This program is free software; you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation; either version 2 of the License, or
 * (at your option) any later version.
 *
 * This program 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 General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program; if not, write to the Free Software
 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
 * MA 02110-1301, USA.
 *
 * The license can be found at https://www.gnu.org/licenses/gpl-3.0.txt
 *
 *
 */

// pins
// GPIO04 SDA
// GPIO05 SCK
// Can't use GPIO16 for interrupta
// GPIO14 Interrupt (Slave data ready)

#define LEDPIN 2
#define INTERRUPT_PIN 14
#define SLAVE1_ADDRESS 0x10
#define SLAVE2_ADDRESS 0x11

#define SERVO_OFF_ANGLE 135
#define SERVO_ON_ANGLE 45

#include <Wire.h>

uint8_t servoAngle = SERVO_OFF_ANGLE;
volatile bool slaveHasData = false;
//uint16_t movementDelay = 10 * 1000; // wait 10 sec before moving the servo again
uint32_t lastMillis = millis();
uint16_t nextHeartbeat = 0;
bool LEDPINStatus = false;

typedef struct ServoInfo {
    uint8_t iicAddress;
    bool moving;
    bool on;
    uint8_t onAngle;
    uint8_t offAngle;
    uint8_t status;
    uint8_t angle;
    uint16_t movementDelay;
} ServoInfo;

struct ServoInfo servoInfo[2] = {{SLAVE1_ADDRESS, false, false, 45, 135, 0, 0, 10 * 1000},
    {SLAVE2_ADDRESS, false, false, 40, 140, 0, 0, 10 * 1000}
};

// interrupt handler for pin change (a Slave is signalling data ready)
void pinChange() {
    //Serial.printf("pinChange Interrupt fired.\r\n"); // servoMoving: %s\n", (servoMoving ? "True" : "False"));
    slaveHasData = true;
}

void MoveServo(uint8_t slaveAddress, uint8_t angle) {
    Wire.beginTransmission(slaveAddress); // transmit to device #8
    Wire.write(angle);              // sends one byte
    if (Wire.endTransmission() == 0) {    // stop transmitting
        Serial.printf("Sent %u to slave %x.\r\n", angle, slaveAddress);
    } else {
        Serial.printf("Send to slave %x failed.\r\n", slaveAddress);
    }
}

bool GetSlaveResponse(struct ServoInfo *slaveInfo) {
    char c;

    uint8_t tmp = slaveInfo->iicAddress;

    //Serial.printf("Wire.requestFrom(%x);\r\n", tmp);

    Wire.requestFrom(tmp, (uint8_t) 2);    // request 2 bytes from slave device

    // wait for (at least) two bytes to arrive
    while (Wire.available() < 2) {
        yield();
    };

    slaveInfo->status = (uint8_t) Wire.read();  // receive a byte as character
    slaveInfo->angle = (uint8_t) Wire.read();  // receive a byte as character

    //Serial.printf("Received status %u, value %u, from slave %x.\r\n", slaveInfo->status, slaveInfo->angle, slaveInfo->iicAddress);

    return true;
}

void controlServo(struct ServoInfo *slaveInfo, bool milliTick) {
    GetSlaveResponse(slaveInfo);

    // have we reached the end of travel?
    slaveInfo->moving = !( slaveInfo->angle == slaveInfo->onAngle || slaveInfo->angle == slaveInfo->offAngle );
    if ( !slaveInfo->moving ) {
        // wait for the delay to elapse
        if (milliTick) {
            if (!--slaveInfo->movementDelay) {
                slaveInfo->movementDelay = 10 * 1000;
                //Serial.print("servoOn: "); Serial.println(servoOn);
                slaveInfo->on = ! slaveInfo->on;
                MoveServo(slaveInfo->iicAddress, (uint8_t)(slaveInfo->on ? slaveInfo->onAngle : slaveInfo->offAngle));
                //Serial.print("servoOn: "); Serial.println(servoOn);
            }
        }
    //} else {
        //if (slaveHasData) {
            //Serial.printf("Slave: %x: angle: %u, Servo moved to: %u.\r\n", slaveInfo->iicAddress, (uint8_t)(slaveInfo->on ? slaveInfo->onAngle : slaveInfo->offAngle), slaveInfo->value);
            //slaveInfo->moving = false;
            //slaveHasData = false;
        //}
    }
}

void setup() {
    Serial.begin(115200);
    Wire.begin(); // join i2c bus (address optional for master)

    pinMode(INTERRUPT_PIN, INPUT);
    attachInterrupt (digitalPinToInterrupt(INTERRUPT_PIN), pinChange, RISING);  // attach interrupt handler

    Serial.println("Master: set up complete");

    delay(10000); // give the slaves time to initialise

    Serial.printf("Getting response from %x\r\n", servoInfo[0].iicAddress);
    GetSlaveResponse(&servoInfo[0]);

    Serial.printf("Getting response from %x\r\n", servoInfo[1].iicAddress);
    GetSlaveResponse(&servoInfo[1]);

    MoveServo(servoInfo[0].iicAddress, (uint8_t)(servoInfo[0].on ? servoInfo[0].onAngle : servoInfo[0].offAngle));
    MoveServo(servoInfo[1].iicAddress, (uint8_t)(servoInfo[1].on ? servoInfo[1].onAngle : servoInfo[1].offAngle));

    Serial.println("setup() complete.");
}

void loop() {
    unsigned long millisNow = millis();
    bool milliTick = (lastMillis != millisNow);
    lastMillis = millisNow;

    if (milliTick) {
        controlServo(&servoInfo[0], milliTick);
        controlServo(&servoInfo[1], milliTick);
    }

    // heartbeat: blink the led on pin1
    if (milliTick) {
        if (!--nextHeartbeat) {
            nextHeartbeat =  500;
            LEDPINStatus = !LEDPINStatus;
            digitalWrite(LEDPIN, LEDPINStatus);
        }
    }
}

The LUA code:


-- Based on work by zeroday & sancho among many other open source authors
-- This code is public domain, attribution to gareth@l0l.org.uk appreciated.
-- adapted by oschreibke@gmail.com

id=0  -- need this to identify (software) IC2 bus?
sda=2 -- connect to pin GPIO4
scl=1 -- connect to pin GPIO5
int=5 -- interrupt pin GPIO14

-- user defined function: see if device responds with ACK to i2c start
function find_dev(i2c_id, dev_addr)
     i2c.start(i2c_id)
     c=i2c.address(i2c_id, dev_addr, i2c.TRANSMITTER)
     i2c.stop(i2c_id)
     return c
end

function i2c_write(dev_addr, data)
     i2c.start(id)
     i2c.address(id, dev_addr, i2c.TRANSMITTER)
     i2c.write(id, data)
     i2c.stop(id)
end
-- user defined function: read from reg_addr content of dev_addr
function i2c_read(dev_addr)
     i2c.start(id)
     i2c.address(id, dev_addr, i2c.RECEIVER)
     c = i2c.read(id, 2)
     i2c.stop(id)
     status = string.byte(c, 2);
     angle = string.byte(c, 1);
     return status, angle
end

--function slaveDone(level)

--end

-- initialize i2c with our id and pins in slow mode :-)
i2c.setup(id, sda, scl, i2c.SLOW);

--gpio.mode(int, gpio.INT, gpio.PULLUP)
--gpio.trig(int, 'up', slaveDone)

if not tmr.create():alarm(5000, tmr.ALARM_AUTO, function()
    for addr = 0x10, 0x11 do
--        print("Scanning for device at address 0x"..string.format("%02X", addr))    
        if find_dev(id, addr)==true then
--            print("Device found at address 0x"..string.format("%02X",addr))
                        --print("Device is wired: SDA to GPIO"..gpio_pin[sda].." - IO index "..sda)
                        --print("Device is wired: SCL to GPIO"..gpio_pin[scl].." - IO index "..scl)

            i2c_read(addr);
            --print("Response from "..string.format("%02X", addr));
            --print(status);
            --print(angle);                    

            if angle ~= 125 then
                i2c_write(addr, 125);
            else
                i2c_write(addr, 75);
            end    

        end
    end
end)
then
  print("Can't create timer")
end

The ATTiny code, runs unchanged irrespective of the ESP8266 code There are two ATTinys, one coded to i2c address 0x10, the other to address 0x11.


/*
 * ATTiny85_iic_ServoController.ino
 *
 * Copyright 2017 Otto Schreibke <oschreibke@gmail.com>
 *
 * This program is free software; you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation; either version 2 of the License, or
 * (at your option) any later version.
 *
 * This program 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 General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program; if not, write to the Free Software
 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
 * MA 02110-1301, USA.
 *
 * The license can be found at https://www.gnu.org/licenses/gpl-3.0.txt
 *
 *
 */

// IIC Controller for a SG90 servo

// Reads the IIC address from the EEPROM - first four bytes = "IIC" + the IIC address
// if the header is not present, will blink the led every 250 ms.
// change backed out. EEPROM does not seem to reliably persist.
// hard-coding the IIC address in the sketch

// hacked version from  https://ladvien.com/robots/attiny-i2c/

// pin usage:
//   0 - IIC SDA
//   2 - IIC SCL
//   3 - controls the servo
//   1 - used for the heartbeat (flashes the led)
//   4 - when high, initiates feedback for the master is present

#define SDA 0
#define SCL 2
#define SERVO_PIN 3
#define LEDPIN 1
#define FEEDBACKPIN 4

// the servo will reset to the on_angle when powered on.

// Get this from https://github.com/rambo/TinyWire
#include <TinyWireS.h>
//#include <avr/eeprom.h>

// The default buffer size, Can't recall the scope of defines right now
#ifndef TWI_RX_BUFFER_SIZE
#define TWI_RX_BUFFER_SIZE ( 16 )
#endif

#include <SimpleServo.h>

// the 7-bit address (remember to change this when programming another slave)
uint8_t IIC_Address = 0x10;

struct {
    uint8_t targetAngle;
    uint8_t currentAngle;
    uint8_t nextServoMove;
    SimpleServo  servo;
} servoInfo;

unsigned long lastMillis = millis();
uint16_t nextHeartbeat = 1;
uint16_t heartbeatSpeed = 500;
bool LEDPINStatus = false;
uint8_t movementDelay = 25;

void requestEvent() {
    TinyWireS.send((uint8_t) digitalRead(FEEDBACKPIN));
    TinyWireS.send(servoInfo.currentAngle);

    // turn off the feedback indicator
    digitalWrite(FEEDBACKPIN, LOW);
}

//Handles receiving i2c data.
void receiveEvent(uint8_t howMany) {
    if (TinyWireS.available()) {
        servoInfo.targetAngle = (uint8_t)TinyWireS.receive();
    }
    // turn off the feedback indicator
    digitalWrite(FEEDBACKPIN, LOW);
}

void setup() {
    // set up the heartbeat
    nextHeartbeat = heartbeatSpeed;
    LEDPINStatus = false;
    pinMode(SDA, INPUT);
    pinMode(SCL, INPUT);
    pinMode(LEDPIN, OUTPUT); // LED
    digitalWrite(LEDPIN, LEDPINStatus);

    pinMode(FEEDBACKPIN, OUTPUT);
    digitalWrite(FEEDBACKPIN, LOW);

    //// get the IIC address from EEPROM
    //if (eeprom_read_byte((uint8_t *)0) == 'I' && eeprom_read_byte((uint8_t *)1) == 'I' && eeprom_read_byte((uint8_t *)2) == 'C') {
        //IIC_Address = eeprom_read_byte((uint8_t *)3);
    //} else {
        //heartbeatSpeed = 100;
    //}

    // Set up the Servo
    movementDelay = 25;

    // set up the servo
    servoInfo.servo.attach(SERVO_PIN);

    // move the servo to show we're awake
    servoInfo.servo.write(80); 
    servoInfo.servo.write(100);

    servoInfo.targetAngle =  servoInfo.currentAngle = 90; // reset to the midpoint
    servoInfo.nextServoMove = movementDelay;
    // digitalWrite(FEEDBACKPIN, HIGH);
    servoInfo.servo.write(servoInfo.targetAngle); // reset to the on angle position

    TinyWireS.begin(IIC_Address);
    //Sets up the onReceive function (what we do if we get stuff).
    TinyWireS.onReceive(receiveEvent);
    //Sets up the onRequest function (what we do if asked to send something).
    TinyWireS.onRequest(requestEvent);

    digitalWrite(FEEDBACKPIN, HIGH);
}

void loop() {
    unsigned long millisNow = millis();
    bool milliTick = (lastMillis != millisNow);
    lastMillis = millisNow;

    //Detects a stop sending command.
    TinyWireS_stop_check();

    // gentle servo move
    if (servoInfo.targetAngle != servoInfo.currentAngle) {
        if (milliTick) {
            if (!--servoInfo.nextServoMove) {
                servoInfo.nextServoMove = movementDelay;
                if (servoInfo.currentAngle < servoInfo.targetAngle)
                    servoInfo.currentAngle++;
                else
                    servoInfo.currentAngle--;
                servoInfo.servo.write(servoInfo.currentAngle);
            }
            digitalWrite(FEEDBACKPIN, (servoInfo.targetAngle == servoInfo.currentAngle ? HIGH : LOW));
        }
    }

    // heartbeat: blink the led on pin1
    if (milliTick) {
        if (!--nextHeartbeat) {
            nextHeartbeat =  heartbeatSpeed;
            LEDPINStatus = !LEDPINStatus;
            digitalWrite(LEDPIN, LEDPINStatus);
        }
    }
}