OK, here is some sample code that should allow you to communicate between an Arduino and the cRIO. Sorry for it being a little longer than I intended. First off, while the format is similar to what we use on the robot, I can not test this out to ensure there are no errors as I do not have the hardware available. There shouldnāt be any syntax errors, but by extracting and making a sample program, I may have introduced some other problem. Hopefully not so severe that you canāt make it work relatively easily.
This sample includes both a read and a write example with the Arduino code handling both. A couple of items to note⦠A write/read transaction is never performed in the same function call. This is because there is a bug in the Arduino wire library that sends a āSTOPā after the first part of the transaction even though it is setup as a SLAVE. There is a fix for this, but I have not had the chance to test it out. This method of splitting the write and read into two parts should always work. Second, there is a bug in the JAVA version of the I2C library that could corrupt data sent to the Arduino if any of the bytes are greater than 127. This is due to how the library combines the ābytesā into "int"s prior to sending and JAVA interprets all bytes as signed. The next version of WPILib will correct this. āCā and Labview users shouldnāt see this problem. Finally, the Arduino code uses an I2C address of 2, while the cRIO uses an address of 4. This is intentional.
The cRIO code is not complete. It only has pieces that can be added into your own code and prints out error messages if the communication fails. The Arduino code, however, is a complete sketch and āshouldā work out of the box. Finally, you need to have at least 3 wires between the cRIO and the Arduino for the Clock, Data, and Ground. Omitting a ground wire between the two will cause the communication to fail.
If you have (find) any errors, let me know and I will try to fix them. Hope this helps.
Mike
cRIO Part
import edu.wpi.first.wpilibj.I2C;
public static byte dataReceived] = {0, 0, 0, 0, 0, 0, 0};
private static byte dataToSend] = {0, 0, 0, 0, 0, 0, 0};
private static I2C i2c = digitalSidecar.getI2C(4);
// In the constructor, add the following line. This puts the i2c device into
// CompatibilityMode, this ensures compliance with the entire i2c spec
i2c.setCompatabilityMode(true);
// This routine retrieves the incrementing counter value from the Arduino and reconstitutes
// it back into a 32 bit integer. This is a rather convoluted way of doing it as JAVA does
// not support an unsigned single byte (bytes are signed)
public int arduino_counter()
{
// Request Command #1 - Return Counter Value ("Register" 1)
i2c.write(1, 0);
// Read 5 bytes of data, with 0 bytes to send. A false return value indicates success
if (i2c.transaction(dataToSend, 0, dataReceived, 5) == false)
{
// If the data returned is indeed the counter, the first byte should be a 1 - identical
// to the value we sent above
if (dataReceived[0] != 1)
System.out.println("Invalid data returned from Arduino - command 1");
else
return (((int) dataReceived[4] * 16777216) +
(((int) dataReceived[3] & 0x000000ff) * 65536) +
(((int) dataReceived[2] & 0x000000ff) * 256) +
((int) dataReceived[1] & 0x000000ff));
}
else
System.out.println("Failure to read from Arduino - command 1");
return 0;
}
// This routine sends up to 6 bytes to place in the Arduino's "read/write" array and
// then reads it back into the public byte array "dataReceived" for verification
public void arduino_write(byte newData], byte length)
{
int i;
// Maximum 6 bytes to send in addition to the "command" byte. Place all the data into
// the byte array.
if (length > 6)
length = 6;
dataToSend[0] = 2;
for (i=0; i<length; i++)
dataToSend* = newData*;
// Send the data to the Arduino. Do not request any return bytes or this function
// will fail
if (i2c.transaction(dataToSend, length + 1, dataReceived, 0) == false)
{
// After successfully sending the data, perform a data read. Since the last
// transaction was a write with a "Command" value of 2, the Arduino will assume
// this is the data to return.
if (i2c.transaction(dataToSend, 0, dataReceived, 7) == false)
{
if (dataReceived[0] != 2)
System.out.println("Invalid data returned from Arduino - command 2");
}
else
System.out.println("Failure to read from Arduino - command 2");
}
else
System.out.println("Failure to send data to Arduino");
}
Arduino Sketch
#include <Wire.h>
byte dataToSend = 0;
unsigned long counter = 0;
byte data2[6] = {11, 12, 13, 14, 15, 16};
void setup()
{
Wire.begin(2); // Start I2C interface (address 2)
Wire.onReceive(i2cReceive); // Receive ISR routine
Wire.onRequest(i2cRequest); // Request (send) ISR routine
}
void loop()
{
delay(10); // 10 milliseond delay
// Increment a counter every loop. Since the ISR may interrupt this code at any time,
// we need to disable interrupts during the increment operation so the ISR can't a
// partially updated value.
noInterrupts();
counter++;
interrupts();
}
// This routine is called by the ISR once a complete transmission is received from the master
void i2cReceive(int count)
{
byte i2cCount; // Loop/Array counter
byte tmp; // temporary byte holder
byte i2cDataR[7]; // 7 Bytes in length as that is the
// maximum that can be sent by the
// cRIO
for (i2cCount = 0; i2cCount < count; i2cCount++) // Read data into local buffer
{ // looping through the entire message
tmp = Wire.read();
if (i2cCount < 7) // If more than 7 bytes in length,
i2cDataR[i2cCount] = tmp; // discard remaining data as somthing
} // is wrong.
// the first byte read is typically what is called the register to be read/written. This
// example utilizes it as a "command" either to be executed or the type of data to be returned
// when a "request" is received.
switch (i2cDataR[0]) // Perform action based on command
{
// Command 1: Return the counter value when the "request" occurs
case 1:
dataToSend = 1; // Set a "global" variable for use by
break; // the i2cRequest routine
// Command 2: Update data 2 array with what ever data is sent (if any) and allow this data
// to be returned to the master if it is requested
case 2:
dataToSend = 2; // Communication for i2cRequest
if (i2cCount > 1) // More than just the command byte
memcpy(&data2[0], &i2cDataR[1], i2cCount < 7 ? // Limit the data to copy to 6 max
i2cCount - 1 : 6); // so as to not overflow the array
}
}
// This routine is called when the master requests the slave send data. A full transaction
// typically includes a Receive envent (register to send) followed by a Request event where the
// slave data is actually transmitted to the master.
void i2cRequest()
{
byte i2cDataW[7];
byte length;
// I use the first byte of the data array to send a comfirmation of the information that follows.
// This allows the cRIO a way to check what "message" is being sent from the Arduino and interpret
// it correctly. While this does limit the actual data part of the message to 6 bytes, the extra
// verification, I feel, is worth it.
switch (dataToSend) // variable set in the i2cReceive event
{
// Return the value of the counter
case 1:
i2cDataW[0] = 1;
memcpy(&i2cDataW[1], &counter, 4);
length = 5;
break;
// Return the contents of the cRIO read/write array
case 2:
i2cDataW[0] = 2;
memcpy(&i2cDataW[1], &data2[0], 6);
length = 7;
break;
// Unknown or invalid command. Send an error byte back
default:
i2cDataW[0] = 0xFF;
length = 1;
}
Wire.write((uint8_t *) &i2cDataW[0], length);
}
**