New I2C library for Teensy3

Yes, I have two T3.2 devices. The first (my slave) has the other library that is using Wire (I2Cdev library for an MPU6050 accelerometer) on pins 18/19. I connected the master and slave to use Wire1 on pins 29/30 (tripled checked that they are not cross-wired). What do you mean by "w/pullups"? When I was using Wire (pins 18/19) I had the pullup set us "I2C_PULLUP_EXT". Does that not apply when using Wire1 (pins 29/30)?

I tried both the basic_scanner and advanced_scanner examples, but neither one gave any output.

w/pullups just means to make sure there are external pullups. To be clear, on T3.2 pins 29/30 means "arduino" pins 29/30 which are backside SMT pads, are you actually connecting to those pads? (using SMT breakout board or something?) In retrospect, Wire1 is a simple software change, but physically on T3.2 may not be an easy thing to do (vs LC,3.5,3.6 which have multiple buses on outer pins).

How is the slave polling the MPU6050, is it using a timer interrupt? If so, and the timing is flexible perhaps it is easier to use a timer to set a flag and move all the I2C comm into the foreground.
 
w/pullups just means to make sure there are external pullups. To be clear, on T3.2 pins 29/30 means "arduino" pins 29/30 which are backside SMT pads, are you actually connecting to those pads? (using SMT breakout board or something?) In retrospect, Wire1 is a simple software change, but physically on T3.2 may not be an easy thing to do (vs LC,3.5,3.6 which have multiple buses on outer pins).

Yes, I am using the backside pads on the T3.2; I have soldered leads to them and verified continuity between them using a DMM. For the "external pullups", I am not an electronics expert. Do I need to physically add resistors into the system in order for this to work? If so, how would I determine how much resistance to add and where? A circuit diagram would be helpful :). It has been my impression that that is unnecessary with the Teensy to add external pullups; everywhere else that calls for pullups I have been able to use internal resistance of the Teensy somehow. I do not need to add resistors in order to use i2c_t3 over Wire on pins 18/19.

How is the slave polling the MPU6050, is it using a timer interrupt? If so, and the timing is flexible perhaps it is easier to use a timer to set a flag and move all the I2C comm into the foreground.

I believe the answer is yes to the question on interrupts. Again, I am very much a novice so will need some guidance on how to "use a timer to set a flag and move all the I2C comm into the foreground".

Here is the code that initializes MPU6050 interrupts:

Code:
 // enable Arduino interrupt detection
    //Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
    //attachInterrupt(0, dmpDataReady, RISING);
    Serial.println(F("Enabling interrupt detection (Teensy external interrupt TeensyIntPin)..."));  //MattC
    pinMode(TeensyIntPin, INPUT); // sets the digital pin as input  //MattC
    attachInterrupt(TeensyIntPin, dmpDataReady, RISING);  //MattC
    mpuIntStatus = mpu.getIntStatus();

    // set our DMP Ready flag so the main loop() function knows it's okay to use it
    Serial.println(F("DMP ready! Waiting for first interrupt..."));
    dmpReady = true;

And here is my complete slave source code:

Code:
// Descriptions: Contains code to interface with various sensors:
// -Gyro/Accelerometer (MPU6050/I2Cdev) - https://github.com/jrowberg/i2cdevlib by Jeff Rowberg <jeff@rowberg.net>
// -Temperature (DS18B20) - http://bildr.org/2011/07/ds18b20-arduino/
// -Hall Effect Sensor - https://diyhacking.com/arduino-hall-effect-sensor-tutorial/
// -AttoPilot Current and Voltage Sensing - https://www.sparkfun.com/products/9028
//
// And for transmission to Taranis handheld radio transmitter via MavLink/FrSky X8R SPort interface:
// http://diydrones.com/profiles/blogs/how-to-get-apm-pixhawk-telemetry-on-your-taranis-brought-to-you

/* ============================================
  I2Cdev device library code is placed under the MIT license
  Copyright (c) 2012 Jeff Rowberg

  Permission is hereby granted, free of charge, to any person obtaining a copy
  of this software and associated documentation files (the "Software"), to deal
  in the Software without restriction, including without limitation the rights
  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
  copies of the Software, and to permit persons to whom the Software is
  furnished to do so, subject to the following conditions:

  The above copyright notice and this permission notice shall be included in
  all copies or substantial portions of the Software.

  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  THE SOFTWARE.
  ===============================================
*/

//MPU6050 Gyro/Accelerometer Includes

#include "I2Cdev2.h"
//#include "Wire.h"
#include "MPU6050_6Axis_MotionApps20a.h"
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050a mpu;
//MPU6050 mpu(0x69); // <-- use for AD0 high
#define OUTPUT_READABLE_REALACCEL


//Temperature Sensor Includes
#include <OneWire.h>


//I2C Communication Includes
//#include "I2C_Anything.h"
#include <i2c_t3.h>
//#include <i2c_t3a.h>


// MAVLINK_FRSKYSPORT Includes
//#include <GCS_MAVLink.h>
#include "FrSkySPort.h"
#define debugSerial           Serial
#define _MavLinkSerial      Serial2
#define START                   1
#define MSG_RATE            10             // Hertz
#include <AltSoftSerial.h>


//Setup LED blinking
#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6)
bool blinkState = false;


// MPU6050 Gyro/Accel control/status vars
bool dmpReady = false;  // set true if DMP init was successful
uint8_t mpuIntStatus;   // holds actual interrupt status byte from MPU
uint8_t devStatus;      // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount;     // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
uint8_t TeensyIntPin = 3; //Identify Teensy interrupt pin

// MPU6050 Gyro/Accel orientation/motion vars
Quaternion q;           // [w, x, y, z]         quaternion container
VectorInt16 aa;         // [x, y, z]            accel sensor measurements
VectorInt16 aaReal;     // [x, y, z]            gravity-free accel sensor measurements
VectorInt16 aaWorld;    // [x, y, z]            world-frame accel sensor measurements
VectorFloat gravity;    // [x, y, z]            gravity vector
float euler[3];         // [psi, theta, phi]    Euler angle container
float ypr[3];           // [yaw, pitch, roll]   yaw/pitch/roll container and gravity vector

// packet structure for InvenSense teapot demo
uint8_t teapotPacket[14] = { '$', 0x02, 0, 0, 0, 0, 0, 0, 0, 0, 0x00, 0x00, '\r', '\n' };

// ======================================================================
// MAVLINK_FRSKYSPORT Declarations

// ******************************************
// Message #0  HEARTHBEAT
uint8_t    ap_type = 0;
uint8_t    ap_autopilot = 0;
uint8_t    ap_base_mode = 0;
uint32_t  ap_custom_mode = 0;
uint8_t    ap_system_status = 0;
uint8_t    ap_mavlink_version = 0;

// Message # 1  SYS_STATUS
uint16_t  ap_voltage_battery = 0;    // 1000 = 1V
int16_t    ap_current_battery = 0;    //  10 = 1A

// Message #24  GPS_RAW_INT
uint8_t    ap_fixtype = 0;                  //   0= No GPS, 1 = No Fix, 2 = 2D Fix, 3 = 3D Fix
uint8_t    ap_sat_visible = 0;           // numbers of visible satelites
// FrSky Taranis uses the first recieved lat/long as homeposition.
int32_t    ap_latitude = 0;               // 585522540;
int32_t    ap_longitude = 0;            // 162344467;
int32_t    ap_gps_altitude = 0;        // 1000 = 1m

// Message #74 VFR_HUD
int32_t    ap_airspeed = 0;
uint32_t  ap_groundspeed = 0;
uint32_t  ap_heading = 0;
uint16_t  ap_throttle = 0;

// FrSky Taranis uses the first recieved value after 'PowerOn' or  'Telemetry Reset'  as zero altitude
int32_t    ap_bar_altitude = 0;    // 100 = 1m
int32_t    ap_climb_rate = 0;      // 100= 1m/s

// Message #27 RAW IMU
int32_t   ap_accX = 0;
int32_t   ap_accY = 0;
int32_t   ap_accZ = 0;

int32_t   ap_accX_old = 0;
int32_t   ap_accY_old = 0;
int32_t   ap_accZ_old = 0;

// ******************************************
// These are special for FrSky
int32_t   adc2 = 0;               // 100 = 1.0V
int32_t     vfas = 0;                // 100 = 1,0V
int32_t     gps_status = 0;     // (ap_sat_visible * 10) + ap_fixtype
// ex. 83 = 8 sattelites visible, 3D lock

// ******************************************
//uint8_t     MavLink_Connected;
//uint8_t     buf[MAVLINK_MAX_PACKET_LEN];

uint16_t  hb_count;

unsigned long MavLink_Connected_timer;
unsigned long hb_timer;
unsigned long acc_timer;

int led = 13;

//mavlink_message_t msg;

// ***************************
AltSoftSerial altSerial;
int DS18S20_Pin = 2; //DS18S20 Signal pin on digital 2 (tempearature sensor)
//Temperature chip i/o
OneWire ds(DS18S20_Pin);  // on digital pin 2
int count = 0;
//=======================================================================

//Arduino Hall Effect Sensor
volatile byte half_revolutions;
unsigned int rpm;
unsigned long timeold;
int US1881_Pin = 4; //US1881 Signal pin on digital 4 (hall effect sensor)

//byte Wiredata[8];
//volatile boolean haveData=false;
//volatile float VFinal;
//volatile float IFinal;
//const byte MY_ADDRESS = 42;

//--------------------------------------------
//Get Volt/Curr Data
#define MEM_LEN 256
int VRaw; //This will store our raw ADC data
int IRaw;
float VFinal; //This will store the converted data
float IFinal;
//--------------------------------------------

//i2c_t3 I2C Comm Declarations
//----------------------------------------------
// Function prototypes
void receiveEvent(size_t count);
void requestEvent(void);

//Memory
uint8_t databuf[MEM_LEN];
volatile uint8_t received;
//----------------------------------------------

// ================================================================
// ===               INTERRUPT DETECTION ROUTINE                ===
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
  mpuInterrupt = true;
}

float getTemp() {
  //returns the temperature from one DS18S20 in DEG Celsius

  byte data[12];
  byte addr[8];

  if ( !ds.search(addr)) {
    //no more sensors on chain, reset search
    ds.reset_search();
    return -1000;
  }

  if ( OneWire::crc8( addr, 7) != addr[7]) {
    Serial.println("CRC is not valid!");
    return -1000;
  }

  if ( addr[0] != 0x10 && addr[0] != 0x28) {
    Serial.print("Device is not recognized");
    return -1000;
  }

  ds.reset();
  ds.select(addr);
  ds.write(0x44, 1); // start conversion, with parasite power on at the end

  byte present = ds.reset();
  ds.select(addr);
  ds.write(0xBE); // Read Scratchpad


  for (int i = 0; i < 9; i++) { // we need 9 bytes
    data[i] = ds.read();
  }

  ds.reset_search();

  byte MSB = data[1];
  byte LSB = data[0];

  //Serial.println(data);

  float tempRead = ((MSB << 8) | LSB); //using two's compliment
  float TemperatureSum = tempRead / 16;

  return TemperatureSum;

}

// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================

void setup() {
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(DS18S20_Pin, INPUT_PULLUP);

  // join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
  Wire.begin(MPU6050_DEFAULT_ADDRESS);
  //TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
  Fastwire::setup(400, true);
#endif

  // initialize serial communication
  // (115200 chosen because it is required for Teapot Demo output, but it's
  // really up to you depending on your project)
  Serial.begin(115200);
  altSerial.begin(115200);
  while (!Serial); // wait for Leonardo enumeration, others continue immediately

  // NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
  // Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
  // the baud timing being too misaligned with processor ticks. You must use
  // 38400 or slower in these cases, or use some kind of external separate
  // crystal solution for the UART timer.

  // initialize device
  Serial.println(F("Initializing I2C devices..."));
  mpu.initialize();

  // verify connection
  Serial.println(F("Testing device connections..."));
  Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));

  // wait for ready
  //Serial.println(F("\nSend any character to begin DMP programming and demo: "));
  //while (Serial.available() && Serial.read()); // empty buffer
  //while (!Serial.available());                 // wait for data
  //while (Serial.available() && Serial.read()); // empty buffer again

  // load and configure the DMP
  Serial.println(F("Initializing DMP..."));
  devStatus = mpu.dmpInitialize();

  // supply your own gyro offsets here, scaled for min sensitivity
  mpu.setXGyroOffset(220);
  mpu.setYGyroOffset(76);
  mpu.setZGyroOffset(-85);
  mpu.setZAccelOffset(1788); // 1688 factory default for my test chip

  // make sure it worked (returns 0 if so)
  if (devStatus == 0) {
    // turn on the DMP, now that it's ready
    Serial.println(F("Enabling DMP..."));
    mpu.setDMPEnabled(true);

    // enable Arduino interrupt detection
    //Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
    //attachInterrupt(0, dmpDataReady, RISING);
    Serial.println(F("Enabling interrupt detection (Teensy external interrupt TeensyIntPin)..."));  //MattC
    pinMode(TeensyIntPin, INPUT); // sets the digital pin as input  //MattC
    attachInterrupt(TeensyIntPin, dmpDataReady, RISING);  //MattC
    mpuIntStatus = mpu.getIntStatus();

    // set our DMP Ready flag so the main loop() function knows it's okay to use it
    Serial.println(F("DMP ready! Waiting for first interrupt..."));
    dmpReady = true;

    // get expected DMP packet size for later comparison
    packetSize = mpu.dmpGetFIFOPacketSize();
  } else {
    // ERROR!
    // 1 = initial memory load failed
    // 2 = DMP configuration updates failed
    // (if it's going to break, usually the code will be 1)
    Serial.print(F("DMP Initialization failed (code "));
    Serial.print(devStatus);
    Serial.println(F(")"));
  }

  // configure LED for output
  pinMode(LED_PIN, OUTPUT);

  // ======================================
  // MAVLINK_FRSKYSPORT Setup
  FrSkySPort_Init();
  _MavLinkSerial.begin(57600);
  debugSerial.begin(57600);
  //MavLink_Connected = 0;
  MavLink_Connected_timer = millis();
  hb_timer = millis();
  acc_timer = hb_timer;
  hb_count = 0;


  pinMode(led, OUTPUT);
  //-----------------------------------------------
  //Get Volt/Curr Data

  //pinMode(12, INPUT);      // Control for Send
  //pinMode(11,INPUT);       // Control for Receive

  // Setup for Master mode, pins 18/19, external pullups, 400kHz, 200ms default timeout
  //Wire.begin(I2C_MASTER, 0x00, I2C_PINS_18_19, I2C_PULLUP_EXT, 400000);
  //Wire.setDefaultTimeout(200000); // 200ms

  //-----------------------------------------------
  pinMode(14, INPUT);
  analogReference(DEFAULT);

  // =====================================
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(US1881_Pin, INPUT_PULLUP);

  Serial.begin(115200);
  attachInterrupt(US1881_Pin, magnet_detect, RISING);//Initialize the intterrupt pin (Arduino digital pin 2)
  half_revolutions = 0;
  rpm = 0;
  timeold = 0;

  //    Wire.begin (MY_ADDRESS);
  //Serial.begin (115200);
  //    Wire.onReceive (receiveEvent);

  //i2c_t3 I2C Teensy Comm Setup
  //------------------------------------------
  // Setup for Slave mode, address 0x66, pins 18/19, external pullups, 400kHz
  Wire1.begin(I2C_SLAVE, 0x66, I2C_PINS_18_19, I2C_PULLUP_EXT, 400000);
  
  // Data init
  received = 0;
  memset(databuf, 0, sizeof(databuf));
  
  // register events
  Wire1.onReceive(receiveEvent);
  Wire1.onRequest(requestEvent);
  //------------------------------------------
}

void magnet_detect()//This function is called whenever a magnet/interrupt is detected by the arduino
{
  half_revolutions++;
  Serial.println("==================detect==================");
}

// called by interrupt service routine when incoming data arrives
//void receiveEvent (int howMany)
//{
//if (howMany >= (sizeof VFinal) + (sizeof IFinal))
//  {
//  I2C_readAnything (VFinal);
//  I2C_readAnything (IFinal);
//  haveData = true;
//  }  // end if have enough data
//
//}  // end of receiveEvent

// ================================================================
// ===                    MAIN PROGRAM LOOP                     ===
// ================================================================

void loop() {

  //--------------------------------------------------------
  //Measurement
  VRaw = analogRead(A0);
  IRaw = analogRead(A1);

  //Conversion
  //VFinal = VRaw/49.44; //45 Amp board
  //VFinal = VRaw/12.99; //90 Amp board
  //VFinal = VRaw/12.99; //180 Amp board

  VFinal = VRaw / 19.6; //90 Amp board

  //IFinal = IRaw/14.9; //45 Amp board
  //IFinal = IRaw/7.4; //90 Amp board
  //IFinal = IRaw/3.7; //180 Amp board

  IFinal = IRaw / 10.36; //Calibrated current

  //Display
  //digitalWrite(ledPin, HIGH);   // set the LED on
  Serial.print("$V");
  if (abs(VFinal) < 10.0) {
    Serial.print(" ");
  }
  Serial.print(VFinal);
  Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters

  //Serial.println("   Volts");
  Serial.print("$A");
  if (abs(IFinal) < 10) {
    Serial.print(" ");
  }
  Serial.print(IFinal * 1.00);
  Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters
  //Serial.println("   Amps");
  //--------------------------------------------------------
  //Wire.beginTransmission(8);
  //  Wire.requestFrom(8, 8);    // request 6 bytes from slave device #8
  //
  //  if(Wire.available())
  //   {
  //     int i = 0;
  //     while(Wire.available())    // slave may send less than requested
  //     {
  //       Wiredata[i] = Wire.receive(); // receive a byte as character
  //       i = i + 1;
  //     }
  //
  //     //A union datatypes makes the byte and float elements share the same piece of memory, which enables conversion from a byte array to a float possible
  //     union Volt_tag {byte Volt_b[4]; float Volt_fval;} Volt_Union;
  //     Volt_Union.Volt_b[0] = Wiredata[0];
  //     Volt_Union.Volt_b[1] = Wiredata[1];
  //     Volt_Union.Volt_b[2] = Wiredata[2];
  //     Volt_Union.Volt_b[3] = Wiredata[3];
  //     Voltage = Volt_Union.Volt_fval;
  //     Serial.print("$V");
  //     Serial.println(Voltage);
  //
  //     union Curr_tag {byte Curr_b[4]; float Curr_fval;} Curr_Union;       //Curr = Drum Revs per Second
  //     Curr_Union.Curr_b[0] = Wiredata[4];
  //     Curr_Union.Curr_b[1] = Wiredata[5];
  //     Curr_Union.Curr_b[2] = Wiredata[6];
  //     Curr_Union.Curr_b[3] = Wiredata[7];
  //     Current = Curr_Union.Curr_fval;
  //     Serial.print("$I");
  //     Serial.println(Current);
  //   }
  //   //Wire.endTransmission();

  //  while(Wire.available())    // slave may send less than requested
  //  {
  //    int c = Wire.receive(); // receive a byte as character
  //    //char c = Wire.read(); // receive a byte as character
  //    Serial.print(c);         // print the character
  //  }
  //Serial.println();
  //============================================================================
  // MPU 6050 Accelerometer
  // if programming failed, don't try to do anything
  if (!dmpReady) return;

  // wait for MPU interrupt or extra packet(s) available
  while (!mpuInterrupt && fifoCount < packetSize) {
    // other program behavior stuff here
    // .
    // .
    // .
    // if you are really paranoid you can frequently test in between other
    // stuff to see if mpuInterrupt is true, and if so, "break;" from the
    // while() loop to immediately process the MPU data
    // .
    // .
    // .
  }

  // reset interrupt flag and get INT_STATUS byte
  mpuInterrupt = false;
  mpuIntStatus = mpu.getIntStatus();

  // get current FIFO count
  fifoCount = mpu.getFIFOCount();

  // check for overflow (this should never happen unless our code is too inefficient)
  if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
    // reset so we can continue cleanly
    mpu.resetFIFO();
    Serial.println(F("FIFO overflow!"));

    // otherwise, check for DMP data ready interrupt (this should happen frequently)
  } else if (mpuIntStatus & 0x02) {
    // wait for correct available data length, should be a VERY short wait
    while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();

    // read a packet from FIFO
    mpu.getFIFOBytes(fifoBuffer, packetSize);

    // track FIFO count here in case there is > 1 packet available
    // (this lets us immediately read more without waiting for an interrupt)
    fifoCount -= packetSize;

    // MPU6050 Gyro/Accel Read and Print Data to Serial
#ifdef OUTPUT_READABLE_REALACCEL

    // display real acceleration, adjusted to remove gravity
    mpu.dmpGetQuaternion(&q, fifoBuffer);
    mpu.dmpGetAccel(&aa, fifoBuffer);
    mpu.dmpGetGravity(&gravity, &q);
    mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);

    Serial.print("$");
    if (aaReal.x >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.x);
    Serial.print("\t");
    if (aaReal.y >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.y);
    Serial.print("\t");
    if (aaReal.z >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.z);
    Serial.println();

#endif

    //============================================================================
    // ======================================
    // MAVLINK_FRSKYSPORT Loop
    uint16_t len;

    //    if (millis() - hb_timer > 1500) {
    //      hb_timer = millis();
    //      if (!MavLink_Connected) {   // Start requesting data streams from MavLink
    //        digitalWrite(led, HIGH);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTENDED_STATUS, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        delay(10);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTRA2, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        delay(10);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_RAW_SENSORS, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        digitalWrite(led, LOW);
    //      }
    //    }
    //
    //    if ((millis() - MavLink_Connected_timer) > 1500)  {  // if no HEARTBEAT from APM  in 1.5s then we are not connected
    //      MavLink_Connected = 0;
    //      hb_count = 0;
    //    }

    //_MavLink_receive();                   // Check MavLink communication

    FrSkySPort_Process();               // Check FrSky S.Port communication

    adc2 = analogRead(0) / 4;            // Read ananog value from A0 (Pin 14). ( Will be A2 value on FrSky LCD)

    if ((millis() - acc_timer) > 1000) {   // Reset timer for AccX, AccY and AccZ
      ap_accX_old = ap_accX;
      ap_accY_old = ap_accY;
      ap_accZ_old = ap_accZ;
      acc_timer = millis();
      //debugSerial.println(adc2);
    }

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

    //    if (count>100) {
    float temperature = getTemp();
    Serial.print("$T");
    Serial.print(temperature);
    Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters
    count = 0;
    //    }
    //    else{
    //      count=count+1;
    //    }

    //Measure RPM
    if (half_revolutions >= 20) {
      rpm = 30 * 1000 / (millis() - timeold) * half_revolutions;
      timeold = millis();
      half_revolutions = 0;
      //Serial.println(rpm,DEC);
    }

    //   if (haveData)
    //   {
    //   Serial.print ("$V");
    //   Serial.println (VFinal);
    //   Serial.print ("$I");
    //   Serial.println (IFinal);
    //   haveData = false;
    //   }  // end if haveData
    //Serial.println();

    // blink LED to indicate activity
    blinkState = !blinkState;
    digitalWrite(LED_PIN, blinkState);
  }
}

//
// handle Rx Event (incoming I2C data)
//
void receiveEvent(size_t count)
{
  size_t idx = 0;

  while (idx < count)
  {
    if (idx < MEM_LEN)                    // drop data beyond mem boundary
      databuf[idx++] = Wire1.readByte(); // copy data to mem
    else
      Wire1.readByte();                  // drop data if mem full
  }

  received = count; // set received flag to count, this triggers print in main loop
}

//
// handle Tx Event (outgoing I2C data)
//
void requestEvent(void)
{
  //Wire1.write(databuf, MEM_LEN); // fill Tx buffer (send full mem)

  char Vf[MEM_LEN];
  sprintf(Vf, "V%f A%f", (double)VFinal, (double)IFinal);
  Wire1.write(Vf);
  Serial.printf("Sending '%s'\n", Vf);
  //Wire1.write((byte)VFinal); // fill Tx buffer (send full mem)
  //Wire1.write(Vfinal); // fill Tx buffer (send full mem)
}
 
2.2kohm pullups are recommended for 3.3v

Ok, I don't have 2.2 kohm, but I have 1.96 kohm. Also my supply voltage is 5V instead of 3.3; does that impact the voltage of the I2C bus?
I am looking at this website to give me a circuit diagram: http://www.edn.com/design/analog/4371297/Design-calculations-for-robust-I2C-communications

Does this look correct?
296877-design_calculations_for_robust_i2c_fig1.jpg
 
for 5v use 4.7k pullups, provided the mcu is 5v tolerant, of course, otherwise for an i2c 3.3v bus use 2.2k

yes that looks correct
1 set of pullups as close to mcu as possible, none on the devices, usually if breakouts have them built in, its better to remove those ones and use your own
 
Yes, I am using the backside pads on the T3.2; I have soldered leads to them and verified continuity between them using a DMM. For the "external pullups", I am not an electronics expert. Do I need to physically add resistors into the system in order for this to work? If so, how would I determine how much resistance to add and where? A circuit diagram would be helpful :). It has been my impression that that is unnecessary with the Teensy to add external pullups; everywhere else that calls for pullups I have been able to use internal resistance of the Teensy somehow. I do not need to add resistors in order to use i2c_t3 over Wire on pins 18/19.

Yes on a T3.2 you could specify internal pullups on the Master device, and for communicating just between two T3.2 devices that can work (note, this is generally not the case on other teensy devices). To specify internal pullups you would change the following line on the Master sketch (leave Slave sketch as I2C_PULLUP_EXT):
Code:
Wire1.begin(I2C_MASTER, 0x00, I2C_PINS_29_30, [COLOR=#ff0000]I2C_PULLUP_INT[/COLOR], 400000);
One reason this may have worked earlier is that the MPU6050 may have pullups already on its board. This is a common thing on some I2C devices.

If you are using an external pullup resistor the value is not too critical, especially on a short line length at standard 400k speeds. Usually anything in the 2k to 5k range will work. There is more information on pullups on the first post in this thread:
https://forum.pjrc.com/threads/21680-New-I2C-library-for-Teensy3?p=27450&viewfull=1#post27450

I would try fixing the pullups first and see if the communication works (it should). Since you are almost there that is the short path versus recoding your sketch to use a common bus.
 
Yes on a T3.2 you could specify internal pullups on the Master device, and for communicating just between two T3.2 devices that can work (note, this is generally not the case on other teensy devices).

Just now got around to this fix, and it worked! Thanks again for all the help.
 
The I2C comm between my 2 Teensys is working wonderfully now. I'm able to stream data between them nicely. I had one other question come up:

In order for my Slave to start streaming data, I need to start it up while connected to a PC and open a Serial monitor in the Arduino IDE. If I don't do this, the Master will not be able to request data via I2C and prints FAIL, indicating Wire1.getError() is true. For my application, I would prefer not to have to connect to a PC Serial monitor every time I want to power up and start streaming data. Is there a way to send some kind of initiation signal from the Master to the Slave via i2c_t3 in order to get the Slave to start it's program?

Here is my new Master code:
Code:
// -Gyro/Accelerometer (MPU6050/I2Cdev) - https://github.com/jrowberg/i2cdevlib by Jeff Rowberg <jeff@rowberg.net>
// -Temperature (DS18B20) - http://bildr.org/2011/07/ds18b20-arduino/
// -Hall Effect Sensor - https://diyhacking.com/arduino-hall-effect-sensor-tutorial/
// -AttoPilot Current and Voltage Sensing - https://www.sparkfun.com/products/9028
//
// And for transmission to Taranis handheld radio transmitter via MavLink/FrSky X8R SPort interface:
// http://diydrones.com/profiles/blogs/how-to-get-apm-pixhawk-telemetry-on-your-taranis-brought-to-you
//
// Also allows for multiple arms to stream data this this Master Teensy via I2C
/* ============================================
  I2Cdev device library code is placed under the MIT license
  Copyright (c) 2012 Jeff Rowberg

  Permission is hereby granted, free of charge, to any person obtaining a copy
  of this software and associated documentation files (the "Software"), to deal
  in the Software without restriction, including without limitation the rights
  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
  copies of the Software, and to permit persons to whom the Software is
  furnished to do so, subject to the following conditions:

  The above copyright notice and this permission notice shall be included in
  all copies or substantial portions of the Software.

  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  THE SOFTWARE.
  ===============================================
*/

//MPU6050 Gyro/Accelerometer Includes

#include <i2c_t3.h>
#include "I2Cdev2.h"
//#include "Wire.h"
#include "MPU6050_6Axis_MotionApps20a.h"
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050a mpu;
//MPU6050 mpu(0x69); // <-- use for AD0 high
#define OUTPUT_READABLE_REALACCEL

//Temperature Sensor Includes
#include <OneWire.h>

// MAVLINK_FRSKYSPORT Includes
//#include <GCS_MAVLink.h>
#include "FrSkySPort.h"
#define debugSerial           Serial
#define _MavLinkSerial      Serial2
#define START                   1
#define MSG_RATE            10             // Hertz
#include <AltSoftSerial.h>

//Setup LED blinking
#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6)
bool blinkState = false;

// MPU6050 Gyro/Accel control/status vars
bool dmpReady = false;  // set true if DMP init was successful
uint8_t mpuIntStatus;   // holds actual interrupt status byte from MPU
uint8_t devStatus;      // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount;     // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
uint8_t TeensyIntPin = 3; //Identify Teensy interrupt pin

// MPU6050 Gyro/Accel orientation/motion vars
Quaternion q;           // [w, x, y, z]         quaternion container
VectorInt16 aa;         // [x, y, z]            accel sensor measurements
VectorInt16 aaReal;     // [x, y, z]            gravity-free accel sensor measurements
VectorInt16 aaWorld;    // [x, y, z]            world-frame accel sensor measurements
VectorFloat gravity;    // [x, y, z]            gravity vector
float euler[3];         // [psi, theta, phi]    Euler angle container
float ypr[3];           // [yaw, pitch, roll]   yaw/pitch/roll container and gravity vector

// packet structure for InvenSense teapot demo
uint8_t teapotPacket[14] = { '$', 0x02, 0, 0, 0, 0, 0, 0, 0, 0, 0x00, 0x00, '\r', '\n' };

// ======================================================================
// MAVLINK_FRSKYSPORT Declarations

// ******************************************
// Message #0  HEARTHBEAT
uint8_t    ap_type = 0;
uint8_t    ap_autopilot = 0;
uint8_t    ap_base_mode = 0;
uint32_t  ap_custom_mode = 0;
uint8_t    ap_system_status = 0;
uint8_t    ap_mavlink_version = 0;

// Message # 1  SYS_STATUS
uint16_t  ap_voltage_battery = 0;    // 1000 = 1V
int16_t    ap_current_battery = 0;    //  10 = 1A

// Message #24  GPS_RAW_INT
uint8_t    ap_fixtype = 0;                  //   0= No GPS, 1 = No Fix, 2 = 2D Fix, 3 = 3D Fix
uint8_t    ap_sat_visible = 0;           // numbers of visible satelites
// FrSky Taranis uses the first recieved lat/long as homeposition.
int32_t    ap_latitude = 0;               // 585522540;
int32_t    ap_longitude = 0;            // 162344467;
int32_t    ap_gps_altitude = 0;        // 1000 = 1m

// Message #74 VFR_HUD
int32_t    ap_airspeed = 0;
uint32_t  ap_groundspeed = 0;
uint32_t  ap_heading = 0;
uint16_t  ap_throttle = 0;

// FrSky Taranis uses the first recieved value after 'PowerOn' or  'Telemetry Reset'  as zero altitude
int32_t    ap_bar_altitude = 0;    // 100 = 1m
int32_t    ap_climb_rate = 0;      // 100= 1m/s

// Message #27 RAW IMU
int32_t   ap_accX = 0;
int32_t   ap_accY = 0;
int32_t   ap_accZ = 0;

int32_t   ap_accX_old = 0;
int32_t   ap_accY_old = 0;
int32_t   ap_accZ_old = 0;

// ******************************************
// These are special for FrSky
int32_t   adc2 = 0;               // 100 = 1.0V
int32_t     vfas = 0;                // 100 = 1,0V
int32_t     gps_status = 0;     // (ap_sat_visible * 10) + ap_fixtype
// ex. 83 = 8 sattelites visible, 3D lock

// ******************************************
//uint8_t     MavLink_Connected;
//uint8_t     buf[MAVLINK_MAX_PACKET_LEN];

uint16_t  hb_count;

unsigned long MavLink_Connected_timer;
unsigned long hb_timer;
unsigned long acc_timer;

int led = 13;

//mavlink_message_t msg;

// ***************************
AltSoftSerial altSerial;
int DS18S20_Pin = 2; //DS18S20 Signal pin on digital 2 (tempearature sensor)
//Temperature chip i/o
OneWire ds(DS18S20_Pin);  // on digital pin 2
int count = 0;
//=======================================================================

//Arduino Hall Effect Sensor
volatile byte half_revolutions;
unsigned int rpm;
unsigned long timeold;
int US1881_Pin = 4; //US1881 Signal pin on digital 4 (hall effect sensor)

//--------------------------------------------
//Setup for I2C Data Streaming and Curr/Vol Reading
#define MEM_LEN 256
char databuf[MEM_LEN];
int VRaw; //This will store our raw ADC data
int IRaw;
float VFinal; //This will store the converted data
float IFinal;
//--------------------------------------------

// ================================================================
// ===               INTERRUPT DETECTION ROUTINE                ===
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
  mpuInterrupt = true;
}

float getTemp() {
  //returns the temperature from one DS18S20 in DEG Celsius

  byte data[12];
  byte addr[8];

  if ( !ds.search(addr)) {
    //no more sensors on chain, reset search
    ds.reset_search();
    return -1000;
  }

  if ( OneWire::crc8( addr, 7) != addr[7]) {
    Serial.println("CRC is not valid!");
    return -1000;
  }

  if ( addr[0] != 0x10 && addr[0] != 0x28) {
    Serial.print("Device is not recognized");
    return -1000;
  }

  ds.reset();
  ds.select(addr);
  ds.write(0x44, 1); // start conversion, with parasite power on at the end

  byte present = ds.reset();
  ds.select(addr);
  ds.write(0xBE); // Read Scratchpad


  for (int i = 0; i < 9; i++) { // we need 9 bytes
    data[i] = ds.read();
  }

  ds.reset_search();

  byte MSB = data[1];
  byte LSB = data[0];

  //Serial.println(data);

  float tempRead = ((MSB << 8) | LSB); //using two's compliment
  float TemperatureSum = tempRead / 16;

  return TemperatureSum;

}

// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================

void setup() {
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(DS18S20_Pin, INPUT_PULLUP);

  // join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
  Wire.begin(MPU6050_DEFAULT_ADDRESS);
  //TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
  Fastwire::setup(400, true);
#endif

  // initialize serial communication
  // (115200 chosen because it is required for Teapot Demo output, but it's
  // really up to you depending on your project)
  Serial.begin(115200);
  altSerial.begin(115200);
  while (!Serial); // wait for Leonardo enumeration, others continue immediately

  // NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
  // Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
  // the baud timing being too misaligned with processor ticks. You must use
  // 38400 or slower in these cases, or use some kind of external separate
  // crystal solution for the UART timer.

  // initialize device
  Serial.println(F("Initializing I2C devices..."));
  mpu.initialize();

  // verify connection
  Serial.println(F("Testing device connections..."));
  Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));

  // wait for ready
  //Serial.println(F("\nSend any character to begin DMP programming and demo: "));
  //while (Serial.available() && Serial.read()); // empty buffer
  //while (!Serial.available());                 // wait for data
  //while (Serial.available() && Serial.read()); // empty buffer again

  // load and configure the DMP
  Serial.println(F("Initializing DMP..."));
  devStatus = mpu.dmpInitialize();

  // supply your own gyro offsets here, scaled for min sensitivity
  mpu.setXGyroOffset(220);
  mpu.setYGyroOffset(76);
  mpu.setZGyroOffset(-85);
  mpu.setZAccelOffset(1788); // 1688 factory default for my test chip

  // make sure it worked (returns 0 if so)
  if (devStatus == 0) {
    // turn on the DMP, now that it's ready
    Serial.println(F("Enabling DMP..."));
    mpu.setDMPEnabled(true);

    // enable Arduino interrupt detection
    //Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
    //attachInterrupt(0, dmpDataReady, RISING);
    Serial.println(F("Enabling interrupt detection (Teensy external interrupt TeensyIntPin)..."));  //MattC
    pinMode(TeensyIntPin, INPUT); // sets the digital pin as input  //MattC
    attachInterrupt(TeensyIntPin, dmpDataReady, RISING);  //MattC
    mpuIntStatus = mpu.getIntStatus();

    // set our DMP Ready flag so the main loop() function knows it's okay to use it
    Serial.println(F("DMP ready! Waiting for first interrupt..."));
    dmpReady = true;

    // get expected DMP packet size for later comparison
    packetSize = mpu.dmpGetFIFOPacketSize();
  } else {
    // ERROR!
    // 1 = initial memory load failed
    // 2 = DMP configuration updates failed
    // (if it's going to break, usually the code will be 1)
    Serial.print(F("DMP Initialization failed (code "));
    Serial.print(devStatus);
    Serial.println(F(")"));
  }

  // configure LED for output
  pinMode(LED_PIN, OUTPUT);

  // ======================================
  // MAVLINK_FRSKYSPORT Setup
  FrSkySPort_Init();
  _MavLinkSerial.begin(57600);
  debugSerial.begin(57600);
  //MavLink_Connected = 0;
  MavLink_Connected_timer = millis();
  hb_timer = millis();
  acc_timer = hb_timer;
  hb_count = 0;


  pinMode(led, OUTPUT);
  //-----------------------------------------------
  //Get Data Over I2C

  pinMode(12, INPUT);      // Control for Send
  pinMode(11, INPUT);      // Control for Receive

  // Setup for Master mode, pins 18/19, external pullups, 400kHz, 200ms default timeout
  Wire1.begin(I2C_MASTER, 0x00, I2C_PINS_29_30, I2C_PULLUP_INT, 400000);
  Wire1.setDefaultTimeout(200000); // 200ms
  memset(databuf, 0, sizeof(databuf));
  //-----------------------------------------------
  pinMode(14, INPUT);
  analogReference(DEFAULT);

  // =====================================
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(US1881_Pin, INPUT_PULLUP);

  Serial.begin(115200);
  attachInterrupt(US1881_Pin, magnet_detect, RISING);//Initialize the intterrupt pin (Arduino digital pin 2)
  half_revolutions = 0;
  rpm = 0;
  timeold = 0;
}

void magnet_detect()//This function is called whenever a magnet/interrupt is detected by the arduino
{
  half_revolutions++;
  Serial.println("==================detect==================");
}

// ================================================================
// ===                    MAIN PROGRAM LOOP                     ===
// ================================================================

void loop() {

  //--------------------------------------------------------
  //Measurement
  VRaw = analogRead(A0);
  IRaw = analogRead(A1);

  //Conversion
  //VFinal = VRaw/49.44; //45 Amp board
  //VFinal = VRaw/12.99; //90 Amp board
  //VFinal = VRaw/12.99; //180 Amp board

  VFinal = VRaw / 19.6; //90 Amp board

  //IFinal = IRaw/14.9; //45 Amp board
  //IFinal = IRaw/7.4; //90 Amp board
  //IFinal = IRaw/3.7; //180 Amp board

  IFinal = IRaw / 10.36; //Calibrated current

  //Display
  //digitalWrite(ledPin, HIGH);   // set the LED on
  Serial.print("$V");
  if (abs(VFinal) < 10.0) {
    Serial.print(" ");
  }
  Serial.print(VFinal * 1.0);
  Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters

  //Serial.println("   Volts");
  Serial.print("$A");
  if (abs(IFinal) < 10) {
    Serial.print(" ");
  }
  Serial.print(IFinal * 1.0);
  Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters

 // MPU 6050 Accelerometer
  // if programming failed, don't try to do anything
  if (!dmpReady) return;

  // wait for MPU interrupt or extra packet(s) available
  while (!mpuInterrupt && fifoCount < packetSize) {
    // other program behavior stuff here
    // .
    // .
    // .
    // if you are really paranoid you can frequently test in between other
    // stuff to see if mpuInterrupt is true, and if so, "break;" from the
    // while() loop to immediately process the MPU data
    // .
    // .
    // .
  }

  // reset interrupt flag and get INT_STATUS byte
  mpuInterrupt = false;
  mpuIntStatus = mpu.getIntStatus();

  // get current FIFO count
  fifoCount = mpu.getFIFOCount();

  // check for overflow (this should never happen unless our code is too inefficient)
  if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
    // reset so we can continue cleanly
    mpu.resetFIFO();
    Serial.println(F("FIFO overflow!"));

    // otherwise, check for DMP data ready interrupt (this should happen frequently)
  } else if (mpuIntStatus & 0x02) {
    // wait for correct available data length, should be a VERY short wait
    while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();

    // read a packet from FIFO
    mpu.getFIFOBytes(fifoBuffer, packetSize);

    // track FIFO count here in case there is > 1 packet available
    // (this lets us immediately read more without waiting for an interrupt)
    fifoCount -= packetSize;

    // MPU6050 Gyro/Accel Read and Print Data to Serial
#ifdef OUTPUT_READABLE_REALACCEL

    // display real acceleration, adjusted to remove gravity
    mpu.dmpGetQuaternion(&q, fifoBuffer);
    mpu.dmpGetAccel(&aa, fifoBuffer);
    mpu.dmpGetGravity(&gravity, &q);
    mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);

    Serial.print("$");
    if (aaReal.x >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.x);
    //Serial.print(' ');
    if (aaReal.y >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.y);
    //Serial.print(' ');
    if (aaReal.z >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.z);
    Serial.println(" a");

#endif

    //============================================================================
    // ======================================
    // MAVLINK_FRSKYSPORT Loop
    uint16_t len;

    //    if (millis() - hb_timer > 1500) {
    //      hb_timer = millis();
    //      if (!MavLink_Connected) {   // Start requesting data streams from MavLink
    //        digitalWrite(led, HIGH);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTENDED_STATUS, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        delay(10);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_EXTRA2, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        delay(10);
    //        mavlink_msg_request_data_stream_pack(0xFF, 0xBE, &msg, 1, 1, MAV_DATA_STREAM_RAW_SENSORS, MSG_RATE, START);
    //        len = mavlink_msg_to_send_buffer(buf, &msg);
    //        _MavLinkSerial.write(buf, len);
    //        digitalWrite(led, LOW);
    //      }
    //    }
    //
    //    if ((millis() - MavLink_Connected_timer) > 1500)  {  // if no HEARTBEAT from APM  in 1.5s then we are not connected
    //      MavLink_Connected = 0;
    //      hb_count = 0;
    //    }

    //_MavLink_receive();                   // Check MavLink communication

    FrSkySPort_Process();               // Check FrSky S.Port communication

    adc2 = analogRead(0) / 4;            // Read ananog value from A0 (Pin 14). ( Will be A2 value on FrSky LCD)

    if ((millis() - acc_timer) > 1000) {   // Reset timer for AccX, AccY and AccZ
      ap_accX_old = ap_accX;
      ap_accY_old = ap_accY;
      ap_accZ_old = ap_accZ;
      acc_timer = millis();
      //debugSerial.println(adc2);
    }

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

    float temperature = getTemp();
    Serial.print("$T");
    Serial.print(temperature);
    Serial.println("          a"); //Note that this extra white space ensures the text string is exactly 18 characters

    //Measure RPM
    if (half_revolutions >= 20) {
      rpm = 30 * 1000 / (millis() - timeold) * half_revolutions;
      timeold = millis();
      half_revolutions = 0;
      //Serial.println(rpm,DEC);
    }

    //============================================================
    //Send Data Over I2C
    uint8_t target = 0x66; // target Slave address
    size_t idx;
    digitalWrite(12, LOW);

    //Set pin 11 LOW to receive
    digitalWrite(11, LOW);

    // Read string from Slave
    if (digitalRead(11) == LOW)
    {
      // Print message
      //Serial.print("Reading from Slave: ");

      // Read from Slave
      Wire1.requestFrom(target, (size_t)MEM_LEN); // Read from Slave (string len unknown, request full buffer)

      // Check if error occured
      if (Wire1.getError())
        Serial.print("FAIL\n");
      else
      {
        // If no error then read Rx data into buffer and print
        idx = 0;
        while (Wire1.available())
          databuf[idx++] = Wire1.readByte();
        Serial.print(databuf);
        Serial.print('\n');
      }

      digitalWrite(LED_BUILTIN, LOW);   // LED off

      //Set pin 11 HIGH to stop recieving
      //digitalWrite(11, HIGH);
      if (digitalRead(11) == HIGH)
      {
        Serial.printf("Set pin 11 HIGH to stop receiving\n\n");
      }
    }
    //============================================================

    // blink LED to indicate activity
    blinkState = !blinkState;
    digitalWrite(LED_PIN, blinkState);
  }
}

And my new slave code:
Code:
// -Gyro/Accelerometer (MPU6050/I2Cdev) - https://github.com/jrowberg/i2cdevlib by Jeff Rowberg <jeff@rowberg.net>
// -Temperature (DS18B20) - http://bildr.org/2011/07/ds18b20-arduino/
// -Hall Effect Sensor - https://diyhacking.com/arduino-hall-effect-sensor-tutorial/
// -AttoPilot Current and Voltage Sensing - https://www.sparkfun.com/products/9028
//
// And for transmission to Taranis handheld radio transmitter via MavLink/FrSky X8R SPort interface:
// http://diydrones.com/profiles/blogs/how-to-get-apm-pixhawk-telemetry-on-your-taranis-brought-to-you

/* ============================================
  I2Cdev device library code is placed under the MIT license
  Copyright (c) 2012 Jeff Rowberg

  Permission is hereby granted, free of charge, to any person obtaining a copy
  of this software and associated documentation files (the "Software"), to deal
  in the Software without restriction, including without limitation the rights
  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
  copies of the Software, and to permit persons to whom the Software is
  furnished to do so, subject to the following conditions:

  The above copyright notice and this permission notice shall be included in
  all copies or substantial portions of the Software.

  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  THE SOFTWARE.
  ===============================================
*/

//MPU6050 Gyro/Accelerometer Includes

#include "I2Cdev2.h"
//#include "Wire.h"
#include "MPU6050_6Axis_MotionApps20a.h"
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050a mpu;
//MPU6050 mpu(0x69); // <-- use for AD0 high
#define OUTPUT_READABLE_REALACCEL


//Temperature Sensor Includes
#include <OneWire.h>


//I2C Communication Includes
#include <i2c_t3.h>

#include <AltSoftSerial.h>


//Setup LED blinking
#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6)
bool blinkState = false;


// MPU6050 Gyro/Accel control/status vars
bool dmpReady = false;  // set true if DMP init was successful
uint8_t mpuIntStatus;   // holds actual interrupt status byte from MPU
uint8_t devStatus;      // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount;     // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
uint8_t TeensyIntPin = 3; //Identify Teensy interrupt pin

// MPU6050 Gyro/Accel orientation/motion vars
Quaternion q;           // [w, x, y, z]         quaternion container
VectorInt16 aa;         // [x, y, z]            accel sensor measurements
VectorInt16 aaReal;     // [x, y, z]            gravity-free accel sensor measurements
VectorInt16 aaWorld;    // [x, y, z]            world-frame accel sensor measurements
VectorFloat gravity;    // [x, y, z]            gravity vector
float euler[3];         // [psi, theta, phi]    Euler angle container
float ypr[3];           // [yaw, pitch, roll]   yaw/pitch/roll container and gravity vector

// packet structure for InvenSense teapot demo
uint8_t teapotPacket[14] = { '$', 0x02, 0, 0, 0, 0, 0, 0, 0, 0, 0x00, 0x00, '\r', '\n' };

AltSoftSerial altSerial;
float temperature;
int DS18S20_Pin = 2; //DS18S20 Signal pin on digital 2 (tempearature sensor)
//Temperature chip i/o
OneWire ds(DS18S20_Pin);  // on digital pin 2
int count = 0;
//=======================================================================

//Arduino Hall Effect Sensor
volatile byte half_revolutions;
unsigned int rpm;
unsigned long timeold;
int US1881_Pin = 4; //US1881 Signal pin on digital 4 (hall effect sensor)

//byte Wiredata[8];
//volatile boolean haveData=false;
//volatile float VFinal;
//volatile float IFinal;
//const byte MY_ADDRESS = 42;

//--------------------------------------------
//Setup I2C Comm and Curr/Volt Readings
#define MEM_LEN 256
int VRaw; //This will store our raw ADC data
int IRaw;
float VFinal; //This will store the converted data
float IFinal;
//--------------------------------------------

//i2c_t3 I2C Comm Declarations
//----------------------------------------------
// Function prototypes
void receiveEvent(size_t count);
void requestEvent(void);

//Memory
#define MEM_LEN 256
uint8_t databuf[MEM_LEN];
volatile uint8_t received;
//----------------------------------------------

// ================================================================
// ===               INTERRUPT DETECTION ROUTINE                ===
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
  mpuInterrupt = true;
}

float getTemp() {
  //returns the temperature from one DS18S20 in DEG Celsius

  byte data[12];
  byte addr[8];

  if ( !ds.search(addr)) {
    //no more sensors on chain, reset search
    ds.reset_search();
    return -1000;
  }

  if ( OneWire::crc8( addr, 7) != addr[7]) {
    Serial.println("CRC is not valid!");
    return -1000;
  }

  if ( addr[0] != 0x10 && addr[0] != 0x28) {
    Serial.print("Device is not recognized");
    return -1000;
  }

  ds.reset();
  ds.select(addr);
  ds.write(0x44, 1); // start conversion, with parasite power on at the end

  byte present = ds.reset();
  ds.select(addr);
  ds.write(0xBE); // Read Scratchpad


  for (int i = 0; i < 9; i++) { // we need 9 bytes
    data[i] = ds.read();
  }

  ds.reset_search();

  byte MSB = data[1];
  byte LSB = data[0];

  //Serial.println(data);

  float tempRead = ((MSB << 8) | LSB); //using two's compliment
  float TemperatureSum = tempRead / 16;

  return TemperatureSum;

}

// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================

void setup() {
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(DS18S20_Pin, INPUT_PULLUP);

  // join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
  Wire.begin(MPU6050_DEFAULT_ADDRESS);
  //TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
  Fastwire::setup(400, true);
#endif

  // initialize serial communication
  // (115200 chosen because it is required for Teapot Demo output, but it's
  // really up to you depending on your project)
  Serial.begin(115200);
  altSerial.begin(115200);
  while (!Serial); // wait for Leonardo enumeration, others continue immediately

  // NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
  // Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
  // the baud timing being too misaligned with processor ticks. You must use
  // 38400 or slower in these cases, or use some kind of external separate
  // crystal solution for the UART timer.

  // initialize device
  Serial.println(F("Initializing I2C devices..."));
  mpu.initialize();

  // verify connection
  Serial.println(F("Testing device connections..."));
  Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));

  // wait for ready
  //Serial.println(F("\nSend any character to begin DMP programming and demo: "));
  //while (Serial.available() && Serial.read()); // empty buffer
  //while (!Serial.available());                 // wait for data
  //while (Serial.available() && Serial.read()); // empty buffer again

  // load and configure the DMP
  Serial.println(F("Initializing DMP..."));
  devStatus = mpu.dmpInitialize();

  // supply your own gyro offsets here, scaled for min sensitivity
  mpu.setXGyroOffset(220);
  mpu.setYGyroOffset(76);
  mpu.setZGyroOffset(-85);
  mpu.setZAccelOffset(1788); // 1688 factory default for my test chip

  // make sure it worked (returns 0 if so)
  if (devStatus == 0) {
    // turn on the DMP, now that it's ready
    Serial.println(F("Enabling DMP..."));
    mpu.setDMPEnabled(true);

    // enable Arduino interrupt detection
    //Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
    //attachInterrupt(0, dmpDataReady, RISING);
    Serial.println(F("Enabling interrupt detection (Teensy external interrupt TeensyIntPin)..."));  //MattC
    pinMode(TeensyIntPin, INPUT); // sets the digital pin as input  //MattC
    attachInterrupt(TeensyIntPin, dmpDataReady, RISING);  //MattC
    mpuIntStatus = mpu.getIntStatus();

    // set our DMP Ready flag so the main loop() function knows it's okay to use it
    Serial.println(F("DMP ready! Waiting for first interrupt..."));
    dmpReady = true;

    // get expected DMP packet size for later comparison
    packetSize = mpu.dmpGetFIFOPacketSize();
  } else {
    // ERROR!
    // 1 = initial memory load failed
    // 2 = DMP configuration updates failed
    // (if it's going to break, usually the code will be 1)
    Serial.print(F("DMP Initialization failed (code "));
    Serial.print(devStatus);
    Serial.println(F(")"));
  }

  // configure LED for output
  pinMode(LED_PIN, OUTPUT);

  pinMode(14, INPUT);
  analogReference(DEFAULT);

  // =====================================
  //Activate internal pullup resistor for DS18S20 temp sensor
  pinMode(US1881_Pin, INPUT_PULLUP);

  Serial.begin(115200);
  attachInterrupt(US1881_Pin, magnet_detect, RISING);//Initialize the intterrupt pin (Arduino digital pin 2)
  half_revolutions = 0;
  rpm = 0;
  timeold = 0;

  //i2c_t3 I2C Teensy Comm Setup
  //------------------------------------------
  // Setup for Slave mode, address 0x66, pins 18/19, external pullups, 400kHz
  Wire1.begin(I2C_SLAVE, 0x66, I2C_PINS_29_30, I2C_PULLUP_EXT, 400000);

  // Data init
  received = 0;
  memset(databuf, 0, sizeof(databuf));

  // register events
  Wire1.onReceive(receiveEvent);
  Wire1.onRequest(requestEvent);
  //------------------------------------------
}

void magnet_detect()//This function is called whenever a magnet/interrupt is detected by the arduino
{
  half_revolutions++;
  Serial.println("==================detect==================");
}

// ================================================================
// ===                    MAIN PROGRAM LOOP                     ===
// ================================================================

void loop() {

  if (received)
  {
    digitalWrite(LED_BUILTIN, HIGH);
    Serial.printf("Slave received: '%s'\n", (char*)databuf);
    received = 0;
    digitalWrite(LED_BUILTIN, LOW);
  }

  //--------------------------------------------------------
  //Measurement
  VRaw = analogRead(A0);
  IRaw = analogRead(A1);

  //Conversion
  //VFinal = VRaw/49.44; //45 Amp board
  //VFinal = VRaw/12.99; //90 Amp board
  //VFinal = VRaw/12.99; //180 Amp board

  VFinal = VRaw / 19.6; //90 Amp board

  //IFinal = IRaw/14.9; //45 Amp board
  //IFinal = IRaw/7.4; //90 Amp board
  //IFinal = IRaw/3.7; //180 Amp board

  IFinal = IRaw / 10.36; //Calibrated current

  //Display
  //digitalWrite(ledPin, HIGH);   // set the LED on
  Serial.print("$V");
  if (abs(VFinal) < 10.0) {
    Serial.print(" ");
  }
  Serial.print(VFinal);
  Serial.println("          b"); //Note that this extra white space ensures the text string is exactly 18 characters

  //Serial.println("   Volts");
  Serial.print("$A");
  if (abs(IFinal) < 10) {
    Serial.print(" ");
  }
  Serial.print(IFinal * 1.00);
  Serial.println("          b"); //Note that this extra white space ensures the text string is exactly 18 characters
  //Serial.println("          b"); //Note that this extra white space ensures the text string is exactly 18 characters
  //Serial.println("   Amps");
  //--------------------------------------------------------

  // MPU 6050 Accelerometer
  // if programming failed, don't try to do anything
  if (!dmpReady) return;

  // wait for MPU interrupt or extra packet(s) available
  while (!mpuInterrupt && fifoCount < packetSize) {
    // other program behavior stuff here
    // .
    // .
    // .
    // if you are really paranoid you can frequently test in between other
    // stuff to see if mpuInterrupt is true, and if so, "break;" from the
    // while() loop to immediately process the MPU data
    // .
    // .
    // .
  }

  // reset interrupt flag and get INT_STATUS byte
  mpuInterrupt = false;
  mpuIntStatus = mpu.getIntStatus();

  // get current FIFO count
  fifoCount = mpu.getFIFOCount();

  // check for overflow (this should never happen unless our code is too inefficient)
  if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
    // reset so we can continue cleanly
    mpu.resetFIFO();
    Serial.println(F("FIFO overflow!"));

    // otherwise, check for DMP data ready interrupt (this should happen frequently)
  } else if (mpuIntStatus & 0x02) {
    // wait for correct available data length, should be a VERY short wait
    while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();

    // read a packet from FIFO
    mpu.getFIFOBytes(fifoBuffer, packetSize);

    // track FIFO count here in case there is > 1 packet available
    // (this lets us immediately read more without waiting for an interrupt)
    fifoCount -= packetSize;

    // MPU6050 Gyro/Accel Read and Print Data to Serial
#ifdef OUTPUT_READABLE_REALACCEL

    // display real acceleration, adjusted to remove gravity
    mpu.dmpGetQuaternion(&q, fifoBuffer);
    mpu.dmpGetAccel(&aa, fifoBuffer);
    mpu.dmpGetGravity(&gravity, &q);
    mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);

    Serial.print("$");
    if (aaReal.x >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.x) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.x);
    //Serial.print(" ");
    //Serial.print("\t");
    if (aaReal.y >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.y) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.y);
    //Serial.print("\t");
    //Serial.print(" ");
    if (aaReal.z >= 0) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 1000) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 100) {
      Serial.print(' ');
    }
    if (abs(aaReal.z) < 10) {
      Serial.print(' ');
    }
    Serial.print(aaReal.z);
    Serial.println(" b");

#endif

    temperature = getTemp();

    Serial.print("$T");
    Serial.print(temperature);
    Serial.println("          b"); //Note that this extra white space ensures the text string is exactly 18 characters

    //Measure RPM
    if (half_revolutions >= 20) {
      rpm = 30 * 1000 / (millis() - timeold) * half_revolutions;
      timeold = millis();
      half_revolutions = 0;
      //Serial.println(rpm,DEC);
    }

    // blink LED to indicate activity
    blinkState = !blinkState;
    digitalWrite(LED_PIN, blinkState);
  }
}

//
// handle Rx Event (incoming I2C data)
//
void receiveEvent(size_t count)
{
  size_t idx = 0;

  while (idx < count)
  {
    if (idx < MEM_LEN)                    // drop data beyond mem boundary
      databuf[idx++] = Wire1.readByte(); // copy data to mem
    else
      Wire1.readByte();                  // drop data if mem full
  }

  received = count; // set received flag to count, this triggers print in main loop
}

//
// handle Tx Event (outgoing I2C data)
//
void requestEvent(void)
{
  //Wire1.write(databuf, MEM_LEN); // fill Tx buffer (send full mem)

  char Vf[MEM_LEN];
  char Af[MEM_LEN];
  char Tf[MEM_LEN]; //17 18 19 20
  char Acc[MEM_LEN];
  char xSpaces[4];
  char ySpaces[4];
  char zSpaces[4];

  sprintf(Vf, "\n$V%5.2f          b\n", (double)VFinal);
  Wire1.write(Vf);
  
  sprintf(Af, "\n$A%5.2f          b\n", (double)IFinal);
  Wire1.write(Af);

  if (aaReal.x >= 0) {
    if (abs(aaReal.x) < 1000) {
      sprintf(xSpaces, "  ");
    }
    if (abs(aaReal.x) < 100) {
      sprintf(xSpaces, "   ");
    }
    if (abs(aaReal.x) < 10) {
      sprintf(xSpaces, "    ");
    }
  }
  else {
    if (abs(aaReal.x) < 1000) {
      sprintf(xSpaces, " ");
    }
    if (abs(aaReal.x) < 100) {
      sprintf(xSpaces, "  ");
    }
    if (abs(aaReal.x) < 10) {
      sprintf(xSpaces, "   ");
    }
  }

  if (aaReal.y >= 0) {
    if (abs(aaReal.y) < 1000) {
      sprintf(ySpaces, "  ");
    }
    if (abs(aaReal.y) < 100) {
      sprintf(ySpaces, "   ");
    }
    if (abs(aaReal.y) < 10) {
      sprintf(ySpaces, "    ");
    }
  }
  else {
    if (abs(aaReal.y) < 1000) {
      sprintf(ySpaces, " ");
    }
    if (abs(aaReal.y) < 100) {
      sprintf(ySpaces, "  ");
    }
    if (abs(aaReal.y) < 10) {
      sprintf(ySpaces, "   ");
    }
  }

  if (aaReal.z >= 0) {
    if (abs(aaReal.z) < 1000) {
      sprintf(zSpaces, "  ");
    }
    if (abs(aaReal.z) < 100) {
      sprintf(zSpaces, "   ");
    }
    if (abs(aaReal.z) < 10) {
      sprintf(zSpaces, "    ");
    }
  }
  else {
    if (abs(aaReal.z) < 1000) {
      sprintf(zSpaces, " ");
    }
    if (abs(aaReal.z) < 100) {
      sprintf(zSpaces, "  ");
    }
    if (abs(aaReal.z) < 10) {
      sprintf(zSpaces, "   ");
    }
  }

  //sprintf(Acc, "$%s%i%s%i%s%ib\n", xSpaces, (int)aaReal.x, ySpaces, (int)aaReal.y, zSpaces, (int)aaReal.z);
  sprintf(Acc, "\n$%5i%5i%5i b\n", (int)aaReal.x, (int)aaReal.y, (int)aaReal.z);
  Wire1.write(Acc);

  sprintf(Tf, "\n$T%5.2f          b\n", temperature);
  Wire1.write(Tf);
  //Serial.print(Tf[0]);Serial.print(Tf[1]);Serial.print(Tf[2]);Serial.print(Tf[3]);
//
//  Serial.print('\n');
//  int i;
//  for (i = 0; i < 18; i = i + 1) {
//  Serial.print(Tf[i]);
//  }
//  Serial.print('\n');
  
  //Serial.printf("Sending '%s'\n", Acc);
  //Wire1.write((byte)VFinal); // fill Tx buffer (send full mem)
  //Wire1.write(Vfinal); // fill Tx buffer (send full mem)
}
 
The I2C comm between my 2 Teensys is working wonderfully now. I'm able to stream data between them nicely. I had one other question come up:

In order for my Slave to start streaming data, I need to start it up while connected to a PC and open a Serial monitor in the Arduino IDE. If I don't do this, the Master will not be able to request data via I2C and prints FAIL, indicating Wire1.getError() is true. For my application, I would prefer not to have to connect to a PC Serial monitor every time I want to power up and start streaming data. Is there a way to send some kind of initiation signal from the Master to the Slave via i2c_t3 in order to get the Slave to start it's program?

Your problem is this line in both sets of code (in the initialization section):
Code:
while (!Serial); // wait for Leonardo enumeration, others continue immediately
This halts the program until the Serial monitor is opened. While it is useful for debugging, it can get in the way otherwise. Try commenting out those lines.
 
Add timeout to "while (!Serial)"

Your code:
Code:
  Serial.begin(115200);
  altSerial.begin(115200);
  while (!Serial); // wait for Leonardo enumeration, others continue immediately

My code:
Code:
	// Teensy3 doesn't reset with Serial Monitor as do Teensy2/++2, or wait for Serial Monitor window
	// Wait here for 10 seconds to see if we will use Serial Monitor, so output is not lost
	while((!Serial) && (millis()<10000));    // wait until serial monitor is open or timeout
This has the result of waiting for serial for a while but not forever. Mostly now I use 5000 msec as timeout. Usually serial starts in a second or so.
 
Your problem is this line in both sets of code (in the initialization section):
Code:
while (!Serial); // wait for Leonardo enumeration, others continue immediately
This halts the program until the Serial monitor is opened. While it is useful for debugging, it can get in the way otherwise. Try commenting out those lines.

That did the trick, thanks!
 
Converting Keypad_I2Ca library to use i2c_t3 instead of Wire.

Hi,

I'm not sure if you can help with this, but I'm trying to convert the Keypad_I2Ca library from Wire, to i2c_t3.

Here's the modified Keypad_I2Ca.h:

Code:
#ifndef KEYPAD_I2Ca_H
#define KEYPAD_I2Ca_H

#include "Keypad.h"
//#include "Wire.h"
#include <i2c_t3.h>

// literals to use to define the width of the port--last parameter in constructors
#define PCA9554 1	// PCA9554 I/O expander device is 1 byte wide
#define PCA9555 2	// PCA9555 I/O expander device is 2 bytes wide
#define PCA9539 2
#define PCA9534 1
#define PCA9535 2
#define TCA6408 1
#define TCA6416 2
#define TCA9539 2


//class Keypad_I2Ca : public Keypad, public TwoWire {
class Keypad_I2Ca : public Keypad, public i2c_t3 {
public:
	Keypad_I2Ca(char* userKeymap, byte* row, byte* col, byte numRows, byte numCols, byte address, byte width = 1) :
	Keypad(userKeymap, row, col, numRows, numCols) 
	{ 
		i2caddr = address; 
		i2cwidth = width;
	}	
	

	// Keypad function
	void begin(char *userKeymap);
	// wire function
	void begin(void);
	// wire function
	void begin(byte address);
	// wire function
	void begin(int address);

	void pin_mode(byte pinNum, byte mode);
	void pin_write(byte pinNum, boolean level);
	int  pin_read(byte pinNum);
	// read initial value for pinState
	word pinState_set( );
	// write a whole byte or word (depending on the port expander chip) to i2c
	void port_write( word i2cportval );
	// access functions for IODIR state copy
	word iodir_read( );
	void iodir_write( word iodir );

private:
	// I2C device address
	byte i2caddr;
	// I2C port expander device width in bytes (1 for 8574, 2 for 8575)
	byte i2cwidth;
	// I2C pin_write state persistant storage
	// least significant byte is used for 8-bit port expanders
	word pinState;
	word iodir_state;    // copy of IODIR register
	void _begin( void );
	void p_write( word i2cportval, byte reg );
};



#endif

Here's the modified Keypad_I2Ca.cpp:

Code:
#include "Keypad_I2Ca.h"

#define IREG 0x00	// input port location
#define OREG 0x01	// output port
#define VREG 0x02	// polarity inversion (not used, but configured)
#define CREG 0x03	// configuration reg - IODIR
#define IODIR 0x03	// common alias for config

// Let the user define a keymap - assume the same row/column count as defined in constructor
void Keypad_I2Ca::begin(char *userKeymap) 
{
	Keypad::begin(userKeymap);
	i2c_t3::begin();
	_begin( );
}


// Initialize I2C
void Keypad_I2Ca::begin(void) 
{
	i2c_t3::begin();
	_begin( );
}


// Initialize I2C
void Keypad_I2Ca::begin(byte address) 
{
	i2caddr = address;
	i2c_t3::begin(address);
	_begin( );
}


// Initialize I2C
void Keypad_I2Ca::begin(int address) 
{
	i2caddr = address;
	i2c_t3::begin(address);
	_begin( );
}


// configure port registers as if just power-on reset
void Keypad_I2Ca::_begin( ) 
{
	p_write( 0xffff, OREG );
	p_write( 0x0000, VREG );
	p_write( 0xffff, IODIR );
	iodir_state = 0xffff;
	pinState = pinState_set( );
} // _begin( )


void Keypad_I2Ca::pin_mode(byte pinNum, byte mode) 
{
	word mask = 1<<pinNum;
	if( mode == OUTPUT ) 
	{
		iodir_state &= ~mask;
	} 
	else 
	{
		iodir_state |= mask;
	}
	p_write( iodir_state, IODIR );
} // pin_mode( )


void Keypad_I2Ca::pin_write(byte pinNum, boolean level) 
{
	word mask = 1<<pinNum;
	if( level == HIGH ) 
	{
		pinState |= mask;
	} 
	else 
	{
		pinState &= ~mask;
	}
	p_write( pinState, OREG );
} // I2CxWrite( )


int Keypad_I2Ca::pin_read(byte pinNum) 
{
	word mask = 0x1<<pinNum;
	i2c_t3::beginTransmission( (int)i2caddr );
	i2c_t3::write( IREG );
	i2c_t3::endTransmission( );
	i2c_t3::requestFrom((int)i2caddr, (int)i2cwidth);
	word pinVal = i2c_t3::read( );
	if (i2cwidth > 1) 
	{
		pinVal |= i2c_t3::read( ) << 8;
	} 
	pinVal &= mask;
	if( pinVal == mask ) 
	{
		return 1;
	} 
	else 
	{
		return 0;
	}
} // pin_read( )

void Keypad_I2Ca::port_write( word i2cportval ) 
{
	p_write( i2cportval, OREG );
} // port_write( ) - public access


void Keypad_I2Ca::p_write( word i2cportval, byte reg ) 
{
	i2c_t3::beginTransmission((int)i2caddr);
	i2c_t3::write( reg<<(i2cwidth-1) );			//twice as many regs for 9555
	i2c_t3::write( i2cportval & 0x00FF );
	if (i2cwidth > 1) 
	{
		i2c_t3::write( i2cportval >> 8 );
	}
	i2c_t3::endTransmission();
	//	if( reg == OREG) pinState = i2cportval;		//not quite right - re-read i/p??
	if( reg == OREG) pinState = pinState_set( );
} // p_write( ) - private


word Keypad_I2Ca::pinState_set( ) 
{
	i2c_t3::beginTransmission( (int)i2caddr );
	i2c_t3::write( IREG );
	i2c_t3::endTransmission( );
	i2c_t3::requestFrom( (int)i2caddr, (int)i2cwidth );
	pinState = i2c_t3::read( );
	if (i2cwidth > 1) 
	{
		pinState |= i2c_t3::read( ) << 8;
	}
	return pinState;
} // set_pinState( )


word Keypad_I2Ca::iodir_read( ) 
{
	//	i2c_t3::requestFrom( (int)i2caddr, (int)i2cwidth );
	//	iodir_state = i2c_t3::read( );
	//	if( i2cwidth > 1 ) {
	//		iodir_state |= i2c_t3::read( ) << 8;
	//	}
	return iodir_state;
} // iodir_read( )


void Keypad_I2Ca::iodir_write( word iodir ) 
{
	p_write( iodir, IODIR );
	iodir_state = iodir;
} // iodir_write( )

Here's the main Sketch code:

Code:
#include <Keypad_I2Ca.h>
#include <Keypad.h>          // GDY120705
//#include <Wire.h>
#include <i2c_t3.h>

#define I2CADDR 0x74

const byte ROWS = 5; //five rows
const byte COLS = 4; //four columns
char keys[ROWS][COLS] =
{
  {'A', 'L', 'm', 'D'},
  {'4', '5', '6', 'H'},
  {'+', '1', '2', '3'},
  {'-', '!', 'O', 'P'},
  {'Q', 'R', 'S', 'T'}
};

byte rowPins[ROWS] = {12, 11, 10, 9, 8}; //connect to the row pinouts of the keypad
byte colPins[COLS] = {13, 14, 15, 0}; //connect to the column pinouts of the keypad


Keypad_I2Ca keypad( makeKeymap(keys), rowPins, colPins, ROWS, COLS, I2CADDR, TCA9539 );
byte ledPin = 13;

boolean blink = false;

void setup() {
  Serial.begin(9600);
  while (!Serial);
  {
    // wait for serial port to connect. Needed for native USB
  }
  Serial.println("--I2C Keypad Test--");
  keypad.begin( );          // GDY120705
  pinMode(ledPin, OUTPUT);      // sets the digital pin as output
  digitalWrite(ledPin, HIGH);   // sets the LED on
  Serial.print("Output Port state = ");
  Serial.println( keypad.iodir_read( ), HEX );
  Serial.print("Input Port state = ");
  Serial.println( keypad.pinState_set( ), HEX );
  keypad.addEventListener(keypadEvent); //add an event listener for this keypad
}

void loop()
{
  char key = keypad.getKey();

  if (key)
  {
    Serial.println(key);
  }
  if (blink)
  {
    digitalWrite(ledPin, !digitalRead(ledPin));
    delay(100);
  }
}

//take care of some special events
void keypadEvent(KeypadEvent key)
{
  switch (keypad.getState())
  {
    case PRESSED:
      switch (key)
      {
        case 'm':
          digitalWrite(ledPin, !digitalRead(ledPin));
          break;
      }
      break;
    case RELEASED:
      switch (key)
      {
        case 'm':
          digitalWrite(ledPin, !digitalRead(ledPin));
          blink = false;
          break;
      }
      break;
    case HOLD:
      switch (key)
      {
        case 'm':
          blink = true;
          break;
      }
      break;
  }
}

When compiling, I get the following errors, but I'm not sure what needs to be changed to correct this.

Code:
Arduino: 1.6.12 (Windows 7), TD: 1.31, Board: "Teensy 3.2 / 3.1, Serial, 96 MHz optimize speed (overclock), US English"

C:\Program Files (x86)\Arduino\arduino-builder -dump-prefs -logger=machine -hardware C:\Program Files (x86)\Arduino\hardware -hardware C:\Users\Ian\AppData\Local\Arduino15\packages -tools C:\Program Files (x86)\Arduino\tools-builder -tools C:\Program Files (x86)\Arduino\hardware\tools\avr -tools C:\Users\Ian\AppData\Local\Arduino15\packages -built-in-libraries C:\Program Files (x86)\Arduino\libraries -libraries D:\Dropbox\Arduino\libraries -fqbn=teensy:avr:teensy31:usb=serial,speed=96opt,keys=en-us -ide-version=10612 -build-path C:\Users\Ian\AppData\Local\Temp\arduino_build_307587 -warnings=default -verbose D:\Dropbox\My Stuff\Teensy\Headunit Stuff\I2C Display Stuff\BusinessKeypad_I2C\BusinessKeypad_I2C.ino
C:\Program Files (x86)\Arduino\arduino-builder -compile -logger=machine -hardware C:\Program Files (x86)\Arduino\hardware -hardware C:\Users\Ian\AppData\Local\Arduino15\packages -tools C:\Program Files (x86)\Arduino\tools-builder -tools C:\Program Files (x86)\Arduino\hardware\tools\avr -tools C:\Users\Ian\AppData\Local\Arduino15\packages -built-in-libraries C:\Program Files (x86)\Arduino\libraries -libraries D:\Dropbox\Arduino\libraries -fqbn=teensy:avr:teensy31:usb=serial,speed=96opt,keys=en-us -ide-version=10612 -build-path C:\Users\Ian\AppData\Local\Temp\arduino_build_307587 -warnings=default -verbose D:\Dropbox\My Stuff\Teensy\Headunit Stuff\I2C Display Stuff\BusinessKeypad_I2C\BusinessKeypad_I2C.ino
Using board 'teensy31' from platform in folder: C:\Program Files (x86)\Arduino\hardware\teensy\avr
Using core 'teensy3' from platform in folder: C:\Program Files (x86)\Arduino\hardware\teensy\avr
Detecting libraries used...
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "D:\Dropbox\Arduino\libraries\Keypad_I2Ca\Keypad_I2Ca.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "D:\Dropbox\Arduino\libraries\Keypad\src\Key.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "D:\Dropbox\Arduino\libraries\Keypad\src\Keypad.cpp" -o "nul"
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3\i2c_t3.cpp" -o "nul"
Generating function prototypes...
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -E -CC -x c++ -w  -g -Wall -ffunction-sections -fdata-sections -nostdlib -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\preproc\ctags_target_for_gcc_minus_e.cpp"
"C:\Program Files (x86)\Arduino\tools-builder\ctags\5.8-arduino10/ctags" -u --language-force=c++ -f - --c++-kinds=svpf --fields=KSTtzns --line-directives "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\preproc\ctags_target_for_gcc_minus_e.cpp"
Compiling sketch...
"C:\Program Files (x86)\Arduino\hardware\teensy/../tools/arm/bin/arm-none-eabi-g++" -c -O -g -Wall -ffunction-sections -fdata-sections -nostdlib -MMD -fno-exceptions -felide-constructors -std=gnu++0x -fno-rtti -mthumb -mcpu=cortex-m4 -fsingle-precision-constant -D__MK20DX256__ -DTEENSYDUINO=131 -DARDUINO=10612 -DF_CPU=96000000 -DUSB_SERIAL -DLAYOUT_US_ENGLISH "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\cores\teensy3" "-ID:\Dropbox\Arduino\libraries\Keypad_I2Ca" "-ID:\Dropbox\Arduino\libraries\Keypad\src" "-IC:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3" "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp" -o "C:\Users\Ian\AppData\Local\Temp\arduino_build_307587\sketch\BusinessKeypad_I2C.ino.cpp.o"
In file included from D:\Dropbox\My Stuff\Teensy\Headunit Stuff\I2C Display Stuff\BusinessKeypad_I2C\BusinessKeypad_I2C.ino:13:0:

D:\Dropbox\Arduino\libraries\Keypad_I2Ca/Keypad_I2Ca.h: In constructor 'Keypad_I2Ca::Keypad_I2Ca(char*, byte*, byte*, byte, byte, byte, byte)':

D:\Dropbox\Arduino\libraries\Keypad_I2Ca/Keypad_I2Ca.h:55:47: error: no matching function for call to 'i2c_t3::i2c_t3()'

  Keypad(userKeymap, row, col, numRows, numCols) 

                                               ^

D:\Dropbox\Arduino\libraries\Keypad_I2Ca/Keypad_I2Ca.h:55:47: note: candidates are:

In file included from D:\Dropbox\Arduino\libraries\Keypad_I2Ca/Keypad_I2Ca.h:38:0,

                 from D:\Dropbox\My Stuff\Teensy\Headunit Stuff\I2C Display Stuff\BusinessKeypad_I2C\BusinessKeypad_I2C.ino:13:

C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:483:5: note: i2c_t3::i2c_t3(uint8_t)

     i2c_t3(uint8_t i2c_bus);

     ^

C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:483:5: note:   candidate expects 1 argument, 0 provided

C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:438:7: note: constexpr i2c_t3::i2c_t3(const i2c_t3&)

 class i2c_t3 : public Stream

       ^

C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:438:7: note:   candidate expects 1 argument, 0 provided

BusinessKeypad_I2C: In function 'void keypadEvent(KeypadEvent)':
BusinessKeypad_I2C:75: warning: enumeration value 'IDLE' not handled in switch 
   switch (keypad.getState())

          ^

Multiple libraries were found for "Keypad.h"
 Used: D:\Dropbox\Arduino\libraries\Keypad
 Not used: C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\Keypad
Using library Keypad_I2Ca in folder: D:\Dropbox\Arduino\libraries\Keypad_I2Ca (legacy)
Using library Keypad at version 3.1.1 in folder: D:\Dropbox\Arduino\libraries\Keypad 
Using library i2c_t3 in folder: C:\Program Files (x86)\Arduino\hardware\teensy\avr\libraries\i2c_t3 (legacy)
Error compiling for board Teensy 3.2 / 3.1.

It looks to be something to do with how the i2c_t3 constructor is being called (or not), but I don't really know enough about constructors and the finer points of class inheritance to figure it out. If someone can point me in the right direction, it would be most appreciated. I've tried to include all the code, but let me know if anything else is required.

Thanks,

Ian.
 
just change the include file, not the Wire.* calls


DO NOT:
i2c_t3::begin();

I think part of the problem, at least my understanding of the problem, is that the Keypad_I2Ca library isn't using Wire.* calls. It's calling the TwoWire methods directly. I figured I needed to do the same with the i2c_t3 library.

Ian.
 
tonton81 is right, you should try converting the "i2c_t3::" method calls into "Wire.", such as "Wire.begin()" and see if that works for you.

The way the library is structured is that in addition to the methods there is an i2cStruct which is a structure associated with each instance (eg. Wire, Wire1, Wire2, ...). That structure has all the configuration information associated with the instance, such as hardware register locations, pins used, bus speeds, etc. Calling the methods directly loses that association, so it can't know what pins to talk to and so forth. This may have worked on old AVR code if there was only a single hardware bus, but it won't work here.

So short answer, try coding the calls as above and see what happens.
 
Well that appears to work fine.

I replaced all instances of "TwoWire::" with "Wire.", and everything compiles and works as hoped.

Thanks for your help.

Ian.
 
Is there a way to get this library to work with the Audiol ibrary?

You'll have to clarify what error you are getting. I've not tried in combination with the audio lib. Note that there is a way to make it behave very similar to stock Wire lib by setting immediate mode, eg:
Code:
Wire.setOpMode(I2C_OP_MODE_IMM);
So if you get an error with default config, then perhaps try adding that line after the Wire.begin().
 
You'll have to clarify what error you are getting. I've not tried in combination with the audio lib. Note that there is a way to make it behave very similar to stock Wire lib by setting immediate mode, eg:
Code:
Wire.setOpMode(I2C_OP_MODE_IMM);
So if you get an error with default config, then perhaps try adding that line after the Wire.begin().

I took the recorder example and commented out the #include <Wire.H> and added #include <i2c_t3.h> and get this.

Code:
Arduino: 1.8.3 (Windows 10), TD: 1.37, Board: "Teensy 3.2 / 3.1, Serial + Keyboard + Mouse + Joystick, 96 MHz (overclock), Smallest Code, US English"

Recorder: In function 'void continueRecording()':
Recorder:160: warning: variable 'usec' set but not used 
     elapsedMicros usec = 0;

                   ^

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o: In function `i2c0_isr':

C:\Dropbox\MySketchesLocal\libraries\Wire/WireKinetis.cpp:790: multiple definition of `i2c0_isr'

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o:C:\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.cpp:1389: first defined here

c:/arduino/hardware/tools/arm/bin/../lib/gcc/arm-none-eabi/5.4.1/../../../../arm-none-eabi/bin/ld.exe: Disabling relaxation: it will not work with multiple definitions

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o: In function `Print::availableForWrite()':

C:\Arduino\hardware\teensy\avr\cores\teensy3/Print.h:81: multiple definition of `i2c1_isr'

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o:C:\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:911: first defined here

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o: In function `Print::availableForWrite()':

C:\Arduino\hardware\teensy\avr\cores\teensy3/Print.h:81: multiple definition of `Wire1'

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o:C:\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:911: first defined here

c:/arduino/hardware/tools/arm/bin/../lib/gcc/arm-none-eabi/5.4.1/../../../../arm-none-eabi/bin/ld.exe: Warning: size of symbol `Wire1' changed from 20 in C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o to 108 in C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o: In function `Print::availableForWrite()':

C:\Arduino\hardware\teensy\avr\cores\teensy3/Print.h:81: multiple definition of `Wire'

C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o:C:\Arduino\hardware\teensy\avr\libraries\i2c_t3/i2c_t3.h:911: first defined here

c:/arduino/hardware/tools/arm/bin/../lib/gcc/arm-none-eabi/5.4.1/../../../../arm-none-eabi/bin/ld.exe: Warning: size of symbol `Wire' changed from 20 in C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\i2c_t3\i2c_t3.cpp.o to 108 in C:\Users\david\AppData\Local\Temp\arduino_build_283074\libraries\Wire\WireKinetis.cpp.o

collect2.exe: error: ld returned 1 exit status

Multiple libraries were found for "SD.h"
 Used: C:\Arduino\hardware\teensy\avr\libraries\SD
 Not used: C:\Arduino\libraries\SD
Multiple libraries were found for "Wire.h"
 Used: C:\Dropbox\MySketchesLocal\libraries\Wire
 Not used: C:\Arduino\hardware\teensy\avr\libraries\Wire
Error compiling for board Teensy 3.2 / 3.1.

This report would have more information with
"Show verbose output during compilation"
option enabled in File -> Preferences.
 
The problem with doing the substitution of Wire.h -> i2c_t3.h, is you have to change all libraries that include Wire.h to also use i2c_t3.h. Typically, this means copying the library to a new directory with a new name, and changing the files to use that name.
 
Hi,
is there any option to send data to multiple slaves in one DMA-mode session? I mean write buffer with 1st slave address and data, 2nd slave addr and data (3th and so on) and then use sendTransmission() function?
 
just out of curiosity of watching the chip registers to see if their intact to make sure i2c bus is operational, does the library have it's own check built in to detect operational bus without writing a request to the device on the bus?
 
Hi,
is there any option to send data to multiple slaves in one DMA-mode session? I mean write buffer with 1st slave address and data, 2nd slave addr and data (3th and so on) and then use sendTransmission() function?

No it cannot do this right now. When you do a beginTransmission(addr) it will clear the Tx buffer, so your 2nd slave data will clear out the 1st slave data. You would have to create some wrapper logic to buffer commands in this way. This would be something like a FIFO queue where you can stack commands, and then the library will issue them one after another until the queue is empty.
 
Back
Top