[ArduRover Project] I2C communication between RPI2 and a Arduino board

Hi all,
i’m using the function writeByte in the MB85RC04 driver code to communicate with a Flora Arduino Board over the I2C bus. the purpose of my program is to control a LED ring (a NeoPixel Ring from Adafruit) connected to the Arduino Board.
LEDs are expected to change color depending on the data sent on the I2C bus. (the final purpose is for example to display red LEDs when i swith to the RTH mode. blue LEDs for the MANUAL mode etc.)
here is my code

FLORA.h

#include <stdint.h>
#include <stdlib.h>
#include <unistd.h>
#include <string>
#include "I2Cdev.h"

class FLORA
{
public:
        uint8_t device_address;
        FLORA(uint8_t address = 0b101010); //0x2a the address of the Arduino board
        uint8_t readByte(uint8_t* data);
        uint8_t writeByte(uint8_t data);
        uint8_t readBytes(uint8_t length, uint8_t* data);
        uint8_t writeBytes(uint8_t length, uint8_t* data);
};

FLORA.cpp

#include "FLORA.h"

FLORA::FLORA(uint8_t address)
{
    this->device_address = address;
}

uint8_t FLORA::readByte(uint8_t* data)
{
    return I2Cdev::readByte(device_address, 0x0, data);
}

uint8_t FLORA::writeByte(uint8_t data)
{
    return I2Cdev::writeByte(device_address, 0x0, data);

}

uint8_t FLORA::writeBytes(uint8_t length, uint8_t* data)
{
    return I2Cdev::writeBytes(device_address, 0x0, length, data);
}

uint8_t FLORA::readBytes(uint8_t length, uint8_t* data)
{
    return I2Cdev::readBytes(device_address, 0x0, length, data);
}

`
and the main program FLORA_test.cpp

#include <stdio.h>
#include <unistd.h>
#include "Navio/I2Cdev.h"
#include "Navio/FLORA.h"

int main()

{
    FLORA flora;

    uint8_t dev_address = flora.device_address;
    uint16_t reg_address = 0;

    // multiple write and read functionality test

    printf("Multiple read/write functionality test!\nWe will write values 'x' 'y' 'w' 'v' 'u' 't' and 's'\nto the addresses of flora: 0x%x\n",dev_address);

    uint8_t data[7] = {'x', 'y', 'w', 'v', 'u', 't', 's'};

    printf("\nWriting data...\n");
    while(true) {
      for (int i=0; i<7; i++) {
          printf("\n\nWriting %c", data[i]);
          flora.writeByte(data[i]);
          sleep(1);
      }
    }

    return 0;

}

the program returns no error but nothing happens on the Arduino Board.
i check the I2C bus and i see the address of the Arduino 0x2a

$
$ll /dev/i2c*
crw-rw---T 1 root i2c 89, 1 Dec 30 00:17 /dev/i2c-1
$ i2cdetect -y 1
 0  1  2  3  4  5  6  7  8  9  a  b  c  d  e  f
00:          -- -- -- -- -- -- -- -- -- -- -- -- --
10: -- -- -- -- -- -- -- -- -- 19 -- UU -- -- 1e --
20: -- -- -- -- -- -- -- -- -- -- 2a -- -- -- -- --
30: -- -- -- -- -- -- -- -- -- -- -- UU -- -- -- --
40: 40 -- -- -- -- -- -- -- 48 -- -- -- -- -- -- --
50: 50 -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
60: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
70: -- -- -- -- -- -- -- 77`

here are the photo of my Rover



What code do you have running on the flora board? And which pin is the neopixel stick data connected to? (I cant see anything wrong with the pi code, except I dont know what xywvuts does)

hi Mathew, on the Arduino Flora Board i run the LED.ino sketch of the MultiWii code. i changed the code to make it compatible with a neopixel ring (instead of the DFRobot LED ring). Everything works fine when i used the Flora Board and an Arduino Pro Mini. With the python example i have the same problem, maybe the I2C bus frequency of the RPI2 is not compatible with the arduino, i’ll try to change it, i let you know

uint8_t data[7] = {‘x’, ‘y’, ‘w’, ‘v’, ‘u’, ‘t’, ‘s’};
data corresponds to the different MultiWii modes: ACRO HORIZON GPS etc.

// Motors on - ACRO mode - blink 3 red 2x3 white 3 blue
//b[0]= 'x';

// Motors on - HORIZON mode -
//b[0]= 'y';

// Motors on - GPS Positi,on Hold mode - blink all blue 
//b[0]= 'w';

// Motors on - GPS RTH mode - constant blue
//b[0]= 'v';

// Motors on - Angle mode - constant 4 red 2x4 white 4 blue
//b[0]= 'u'; 

// Motors off - Uncalibrated acc / not level- green blink
//b[0]= 't';`

finally I was able to get by using a Python script and the dronekit library
i used the write_byte function instead of the write_byte_data

this Python script connects to Mavlink and detect the VehicleMode of the Rover then sends this information to the Arduino Board over the I2C bus

 #!/usr/bin/python
 """
 sudo python mavlinkToArduino.py
 """

 import smbus
 import time
 
 # Import DroneKit-Python
 from dronekit import connect, VehicleMode
 
 #Set up option parsing to get connection string
 import argparse
 parser = argparse.ArgumentParser(description='Print out vehicle state information. Connects to SITL on local PC by      default.')
 parser.add_argument('--connect', default='udp:127.0.0.1:14550',
                    help="vehicle connection target. Default 'udp:127.0.0.1:14550'")
 args = parser.parse_args()


 # Connect to the Vehicle.
 #   Set `wait_ready=True` to ensure default attributes are populated before `connect()` returns.
 print "\nConnecting to vehicle on: %s" % args.connect
 vehicle = connect(args.connect, wait_ready=True)
 
 bus = smbus.SMBus(1)
 address = 0x2a
 vehicleModeName = ''
 
 buffer = ['x', 'y', 'w', 'v', 'u', 't', 's']
 
 def write(char):
     try:
         print 'Write ', char,' or ',str(ord(char)),' to address ' + str(hex(address))
         bus.write_byte(address,ord(char))
         time.sleep(0.1)
     except:
         return
 
 '''
 for i in buffer:
     for j in range(100):
         write(i)
 '''

 # Get some vehicle attributes (state)
 print "Get some vehicle attribute values:"
 print " GPS: %s" % vehicle.gps_0
 print " Battery: %s" % vehicle.battery
 print " Last Heartbeat: %s" % vehicle.last_heartbeat
 print " Is Armable?: %s" % vehicle.is_armable
 print " System status: %s" % vehicle.system_status.state
 print " Mode: %s" % vehicle.mode.name    # settable
 
 mode = {'AUTO': 's', 'GUIDED': 's', 'MANUAL':'x', 'LEARNING':'u', 'RTL':'v', 'INITIALISING':'t', 'HOLD':'w',      'STEERING':'y'}

 # Show how to add and remove and attribute observer callbacks (using mode as example)
 def mode_callback(self, attr_name, value):
     print "CALLBACK: Mode changed to: ", value
     return
 
 print "\nAdd mode attribute observer for Vehicle.mode"
 vehicle.add_attribute_listener('mode', mode_callback)
 
 
 while True:
     if vehicle.mode.name == 'AUTO': write(mode['AUTO'])
     if vehicle.mode.name == 'GUIDED': write(mode['GUIDED'])
     if vehicle.mode.name == 'MANUAL': write(mode['MANUAL'])
     if vehicle.mode.name == 'LEARNING': write(mode['LEARNING'])
     if vehicle.mode.name == 'RTL': write(mode['RTL'])
     if vehicle.mode.name == 'INITIALISING': write(mode['INITIALISING'])
     if vehicle.mode.name == 'HOLD': write(mode['HOLD'])
     if vehicle.mode.name == 'STEERING': write(mode['STEERING'])
     print " Mode: %s" % vehicle.mode.name

 #Close vehicle object before exiting script
 print "\nClose vehicle object"
 vehicle.close()