MRF24J40 Bluetooth Bridge

So, I got my wireless bridge working. Here are pictures of my setup, an Adafruit Ultimate GPS module happily sending its location to my Android phone.

The Arduino sitting out of my window on the roof is connected to the GPS receiver and one of the two MRF24J40MA modules. Both MRF modules are connected up as described in the previous post. I had a little trouble connecting the GPS receiver, because one of the preferred pins on the Arduino was already in use by the wireless module. I couldn’t get it to work with other pins over SoftwareSerial, so I connected it to the Serial1 pins of the Arduino Mega. Not sure how I will do that if I end up using a different Arduino for the boat, with only one serial interface. Not sure if it was coincidence, but the problematic pin happend to be Arduinos first interrupt pin. I don’t know if the GPS library relies on using interrupts, but this was the only way I found to make it work.

The wireless transceiver is sending the data gathered by the Arduino outside to another Arduino, which just forwards the data to the Amarino bluetooth library, finally sending it to the Android phone where I interpret it and for now just show it as a toast message. The communication goes both ways, sending commands from the phone over Bluetooth and the ZigBee connection to the Arduino Mega, which eventually will drive the boat.

The only thing I still have to figure out is why the reported position is about 50km off of my actual position.

Code

The Java code for Android is a little too complex to post it here, I’ll try to summarize the essential parts.

import at.abraxas.amarino.Amarino;
import at.abraxas.amarino.AmarinoIntent;
 
public class APControlActivity extends Activity {
	static String btBoat = "00:11:12:xx:xx:xx";
	private ArduinoReceiver arduinoReceiver = new ArduinoReceiver();
 
	@Override
	protected void onStart() {
		super.onStart();
		registerReceiver(arduinoReceiver, new IntentFilter(AmarinoIntent.ACTION_RECEIVED));
		Amarino.connect(this, btBoat);
	}
 
	@Override
	protected void onStop() {
		super.onStop();
		Amarino.disconnect(this, btBoat);
		unregisterReceiver(arduinoReceiver);
	}
 
	// BroadcastReceiver from Amarinos Sensor Graph example
	public class ArduinoReceiver extends BroadcastReceiver {
		@Override
		public void onReceive(Context context, Intent intent) {
			String data = null;
 
			final int dataType = intent.getIntExtra(AmarinoIntent.EXTRA_DATA_TYPE, -1);
 
			if (dataType == AmarinoIntent.STRING_EXTRA){
				data = intent.getStringExtra(AmarinoIntent.EXTRA_DATA);
 
				if (data != null) {
					String[] parts = data.split(":");
					if (parts[0] == "ERR") {
						Toast toast = Toast.makeText(context, parts[1], Toast.LENGTH_LONG);
						toast.show();
					}
					else if (parts[0].equals("GPF")) {
					    // sprintf(message,"GPF:%d:%d:%s:%c:%s:%c:%s:%s:%d", GPS.fix,GPS.fixquality,latitude,GPS.lat,longitude,GPS.lon,speed,angle,GPS.satellites);
 
						float lat = Float.parseFloat(parts[3]);
						lat /= 100;
						float lon = Float.parseFloat(parts[5]);
						lon /= 100;
						Toast toast = Toast.makeText(context, String.format("%.6f; %.6f", lat,lon), Toast.LENGTH_LONG);
						toast.show();
					}
					else {
						Toast toast = Toast.makeText(context, data, Toast.LENGTH_SHORT);
						toast.show();
					}
				}
 
			}
		}
	}
}
 
// example on sending data from another class
Amarino.sendDataToArduino(_context, APControlActivity.btBoat, 'a', String.format("SPD:%d", level));

Arduino code on the bridge (using Amarino and Mrf24j40-arduinio-library)

#include <SPI.h>
#include <mrf24j.h>
#include <MeetAndroid.h>
 
// pins needed by the mrf module
const int pin_reset = 6;
const int pin_cs = 7;
const int pin_interrupt = 2;
 
// settings for the ZigBee network
const int wifi_address_controller = 0x4201;
const int wifi_address_boat = 0x4202;
const int wifi_pan = 0x47CC;
 
Mrf24j mrf(pin_reset, pin_cs, pin_interrupt);
 
// bluetooth
MeetAndroid meetAndroid;
 
void setup() {
  Serial.begin(115200);
 
  // initialize the mrf module
  mrf.reset();
  mrf.init();
 
  mrf.set_pan(wifi_pan);
  mrf.address16_write(wifi_address_controller); 
 
  // attach interrupt handler for mrf module
  attachInterrupt(0, interrupt_routine, CHANGE);
  last_time = millis();
  interrupts();
 
  // register handler for data from bluetooth
  meetAndroid.registerFunction(btReceived, 'a');  
}
 
// mrf interrupt handler
void interrupt_routine() {
    mrf.interrupt_handler();
}
 
void loop() {
    mrf.check_flags(&amp;handle_rx, &amp;handle_tx);
    meetAndroid.receive();
    delay(100);
}
 
// mrf receive handler
void handle_rx() {
    char data[mrf.rx_datalength()];
    for (int i = 0; i &lt; mrf.rx_datalength(); i++) {         data[i] = mrf.get_rxinfo()-&gt;rx_data[i];
    }
    // just forward over bluetooth
    meetAndroid.send(data);
}
 
// mrf transfer handler
void handle_tx() {
    if (mrf.get_txinfo()-&gt;tx_ok) {
    } else {
        // send back error message
        char msg[64];
        sprintf(msg, "ERR:TX failed after %d retries", mrf.get_txinfo()-&gt;retries);
        meetAndroid.send(msg);
    }
}
 
// --- bluetooth ---
// bluetooth handler
void btReceived(byte flag, byte numOfValues)
{
  // just forward over mrf
  int length = meetAndroid.stringLength();
  char data[length];
  meetAndroid.getString(data);
  mrf.send16(wifi_address_boat, data);
}

Arduino code on the boat (not cleaned up yet, using the mrf24j40-arduino-library and the Adafruit GPS library)

#include <SPI.h>
#include <mrf24j.h>
#include <Adafruit_GPS.h>
/*#if ARDUINO &gt;= 100
 #include 
#else
  // Older Arduino IDE requires NewSoftSerial, download from:
  // http://arduiniana.org/libraries/newsoftserial/
 #include 
 // DO NOT install NewSoftSerial if using Arduino 1.0 or later!
#endif*/
 
// boat
int motorL = 5;
int motorR = 6;
int minValue = 70;
int maxValue = 230;
int incomingByte = 0;   // for incoming serial data
int currentByte = 0;
int readValue = 0;
 
int speed = 0;
float steering = 0;
 
// wireless
const int pin_reset = 6;
const int pin_cs = 7; // default CS pin on ATmega8/168/328
const int pin_interrupt = 2; // default interrupt pin on ATmega8/168/328
const int wifi_address_controller = 0x4201;
const int wifi_address_boat = 0x4202;
const int wifi_pan = 0x47CC;
 
long last_time;
long tx_interval = 1000;
 
Mrf24j mrf(pin_reset, pin_cs, pin_interrupt);
 
// GPS
/*#if ARDUINO &gt;= 100
  SoftwareSerial mySerial(3, 4);
#else
  NewSoftSerial mySerial(3, 4);
#endif*/
Adafruit_GPS GPS(&amp;Serial1);
 
boolean usingInterrupt = false;
void useInterrupt(boolean); // Func prototype keeps Arduino 0023 happy
 
uint32_t timer = millis();
 
void setup() {
  Serial.begin(115200);
 
  // initialize mrf module
  mrf.reset();
  mrf.init();
 
  mrf.set_pan(wifi_pan);
  mrf.address16_write(wifi_address_boat); 
 
  attachInterrupt(0, wifi_handle_interrupt, CHANGE);
  last_time = millis();
  interrupts();
 
  // initialize GPS module
  GPS.begin(9600);
  GPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCGGA);
  GPS.sendCommand(PMTK_SET_NMEA_UPDATE_1HZ);
  useInterrupt(true);
}
 
void loop() {
    mrf.check_flags(&amp;handle_rx, &amp;handle_tx);
    unsigned long current_time = millis();
    if (current_time - last_time &gt; tx_interval) {
        last_time = current_time;
    }
 
  if (GPS.newNMEAreceived()) {
    if (!GPS.parse(GPS.lastNMEA()))   // this also sets the newNMEAreceived() flag to false
      return;  // we can fail to parse a sentence in which case we should just wait for another
  }
  if (timer &gt; millis())  timer = millis();
 
  if (millis() - timer &gt; 2000) { 
    timer = millis(); // reset the timer
 
    char message[64];
    if (GPS.fix) {
      // workaround for sprintf("%f"); bug
      char latitude[10];
      dtostrf(GPS.latitude,6,4, latitude);
      char longitude[10];
      dtostrf(GPS.longitude,6,4, longitude);
      char speed[6];
      dtostrf(GPS.speed,4,2, speed);
      char angle[7];
      dtostrf(GPS.angle,4,2, angle);
      sprintf(message,"GPF:%d:%d:%s:%c:%s:%c:%s:%s:%d", GPS.fix,GPS.fixquality,latitude,GPS.lat,longitude,GPS.lon,speed,angle,GPS.satellites);
    }
    else {
      sprintf(message,"GPS:%d:%d:%d", (int)GPS.fix,(int)GPS.fixquality,GPS.satellites);
    }
    Serial.println(message);
    mrf.send16(wifi_address_controller, message);
  }
 
}
 
void setSpeed(byte flag, byte numOfValues) {
  speed = minValue + (((maxValue - minValue)/ 100) * 0); //meetAndroid.getInt());
  setMotors();
}
 
void setSteering(byte flag, byte numOfValues) {
  steering = 0; //meetAndroid.getFloat();
  setMotors();
}
 
int steeringMultiplyer = 10;
 
void setMotors() {
  int lSpeed = speed;
  int rSpeed = speed;
  if (steering &lt; 0) {     rSpeed -= (steering * steeringMultiplyer);   }   if (steering &gt; 0) {
    lSpeed += (steering * steeringMultiplyer);
  }
  if (lSpeed &gt; maxValue) {
    lSpeed = maxValue;
  }
  if (rSpeed &gt; maxValue) {
    rSpeed = maxValue;
  }
  analogWrite(motorL, lSpeed);
  analogWrite(motorR, rSpeed);
}
 
// --- Wireless ---
 
void wifi_handle_interrupt() {
    mrf.interrupt_handler(); // mrf24 object interrupt routine
}
 
void handle_rx() {
    Serial.print("received a packet ");Serial.print(mrf.get_rxinfo()-&gt;frame_length, DEC);Serial.println(" bytes long");
 
    if(mrf.get_bufferPHY()){
      Serial.println("Packet data (PHY Payload):");
      for (int i = 0; i &lt; mrf.get_rxinfo()-&gt;frame_length; i++) {
          Serial.print(mrf.get_rxbuf()[i]);
      }
    }
 
    Serial.println("\r\nASCII data (relevant data):");
    for (int i = 0; i &lt; mrf.rx_datalength(); i++) {         Serial.write(mrf.get_rxinfo()-&gt;rx_data[i]);
    }
 
    Serial.print("\r\nLQI/RSSI=");
    Serial.print(mrf.get_rxinfo()-&gt;lqi, DEC);
    Serial.print("/");
    Serial.println(mrf.get_rxinfo()-&gt;rssi, DEC);
}
 
void handle_tx() {
    if (mrf.get_txinfo()-&gt;tx_ok) {
        Serial.println("TX went ok, got ack");
    } else {
        Serial.print("TX failed after ");Serial.print(mrf.get_txinfo()-&gt;retries);Serial.println(" retries\n");
    }
}
 
// --- GPS ---
 
// Interrupt is called once a millisecond, looks for any new GPS data, and stores it
SIGNAL(TIMER0_COMPA_vect) {
  char c = GPS.read();
  // if you want to debug, this is a good time to do it!
}
 
void useInterrupt(boolean v) {
  if (v) {
    // Timer0 is already used for millis() - we'll just interrupt somewhere
    // in the middle and call the "Compare A" function above
    OCR0A = 0xAF;
    TIMSK0 |= _BV(OCIE0A);
    usingInterrupt = true;
  } else {
    // do not call the interrupt function COMPA anymore
    TIMSK0 &amp;= ~_BV(OCIE0A);
    usingInterrupt = false;
  }
}

Published by

Gerald

Diplom-Informatiker (DH) in Darmstadt. Ich blogge über Entwicklung, Internet, mobile Geräte und Virtualisierung. Meine Beiträge gibt es auch bei Google+ und Facebook.

2 thoughts on “MRF24J40 Bluetooth Bridge”

Leave a Reply to Sergio Duarte Cancel reply

Your email address will not be published. Required fields are marked *