Interaction Design WikiSystems Engineering

Arduino BLE

Many Arduino devices come equipped with BLE, or Bluetooth Low Energy modules. BLE allows you to send and receive small amounts of data over relatively short distances, and with very little power consumption. For your Arduino project, it can provide a relatively simple means of communicating from your computer or smartphone or creating a mesh network between Arduinos.

In BLE language, devices can either be a central device (a client), or peripheral devices (server). A peripheral device can provide any number of services, which are like billboards where messages can be read and/or written to by central devices. Each service has a UUID (Universal Unique Identifier). New UUID can be generated with online tools. A typical UUID might look like this:

19B10000-E8F2-537E-4F6C-D104768A1214

In the examples below, this UUID is used. You may need to change this if someone nearby uses the same UUID.

The individual notes on the message board are called characteristics, and they have their own UUID and value. This UUID can specify a. We can make these values read-only, for example, for the value of a temperature sensor. Or, we can make them readable and writable, for example, for controlling the speed of a motor connected to Arduino.

Arduino Code

The ArduinoBLE library is very big! We have good experience using version 1.1.1, which is smaller than the latest. This version is compatible with the 1.5 wifiNina firmware.

This basic example assumes you are using the Arduino Uno Wifi Rev 2. This example can work on other boards too, with some minor modifications. You will also need a way of communicating with the BLE device: You can use an app like BLE Scanner or with the browser using the P5.js example below.

#include <ArduinoBLE.h>
#include <Arduino_LSM6DS3.h> // the IMU used on the Uno Wifi rev 2

BLEService arduinoBleService("19B10000-E8F2-537E-4F6C-D104768A1214"); // create service

// create characteristics and allow remote device to read and write
BLEBoolCharacteristic LEDCharacteristic("19B10001-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
BLECharacteristic accelerationCharacteristic ("19B10014-E8F2-537E-4F6C-D104768A1214", BLENotify, sizeof(float) * 3);

void setup() {
  Serial.begin(9600);
  delay(100);
  // begin initialization
  if (!BLE.begin()) {
    Serial.println("starting BLE failed!");
    while (1);
  }

  if (!IMU.begin()) {
    Serial.println("Failed to initialize IMU!");
    while (1);
  }

  // set the local name peripheral advertises
  BLE.setLocalName("arduinoBLEdemo");
  // set the UUID for the service this peripheral advertises:
  BLE.setAdvertisedService(arduinoBleService);
  
  // add the characteristics to the service
  arduinoBleService.addCharacteristic(LEDCharacteristic);
  arduinoBleService.addCharacteristic(accelerationCharacteristic);

  // add the service
  BLE.addService(arduinoBleService);

  // start advertising
  BLE.advertise();

  Serial.println("Bluetooth device active, waiting for connections...");

  pinMode(LED_BUILTIN, OUTPUT);
}

void loop() {
  // listen for BLE peripherals to connect:
  BLEDevice central = BLE.central();
  // if a central is connected to peripheral:
  if (central) {
    Serial.print("Connected to central: ");
    // print the central MAC address:
    Serial.println(central.address());
    // while the central is still connected to peripheral:

    while (central.connected()) {
      // note: we will stay in this loop as long as we are connected via BLE!
      if (LEDCharacteristic.written()) {
        bool newValue;
        newValue = LEDCharacteristic.value();
        Serial.print("LED : ");
        Serial.println(newValue);
        digitalWrite(LED_BUILTIN, newValue);
      }
      // code for making the IMU data available over bluetooth
      if (accelerationCharacteristic.subscribed() && IMU.accelerationAvailable()) {
        float acceleration[3];
        // x, y, z
        IMU.readAcceleration(acceleration[0], acceleration[1], acceleration[2]);
        accelerationCharacteristic.writeValue(acceleration, sizeof(acceleration));
      }
    }
  }
}

Basic BLE communication in P5.js using Web Bluetooth API.

Note: for this example to work, you must use Chrome. You may also need to enable web Web Bluetooth API at chrome://flags/#enable-experimental-web-platform-features.

Web Bluetooth API also requires a HTTPS site. Running the examples on OpenProcesing will do this by default. This example filters for the specific serviceUuid, which needs to match your Arduino example.

let bleConnected = false;
const serviceUuid = "19b10000-e8f2-537e-4f6c-d104768a1214";
let myCharacteristics = [];
let ledState = 0;
//IMU data 
let ax = 0.0;
let ay = 0.0;
let az = 0.0;

function setup() {
	createCanvas(400, 400, WEBGL);
	// Create a 'Connect' button
	const connectButton = createButton('Connect')
	connectButton.mousePressed(connectToBle);
	connectButton.position(20, 20);
	// led button
	const LEDSButton = createButton('LED Switch')
	LEDSButton.mousePressed(switchLED);
	LEDSButton.position(20, 40);
}

function draw() {
	background(100);
	normalMaterial();
	rotateX(ax);
	rotateY(ay);
	rotateZ(az);
	box(200, 200);
}


function switchLED() {
	if (bleConnected) {
		ledState = 1 - ledState; // toggle value between 0 and 1
		writeToCharacteristic(myCharacteristics[0], ledState) // write to first Characteristic
	}
}

function connectToBle() {
	log('Requesting Bluetooth Device...');
	navigator.bluetooth.requestDevice({
			filters: [{
				services: [serviceUuid]
			}]
		})
		.then(device => {
			console.log('Connecting to GATT Server...');
			return device.gatt.connect();
		})
		.then(server => {
			console.log('Getting Service...');
			return server.getPrimaryService(serviceUuid);
		})
		.then(service => {
			bleConnected = true;
			console.log('Getting all Characteristics...');
			return service.getCharacteristics();
		})
		.then(characteristics => {
			for (const c in characteristics) {
				myCharacteristics.push(characteristics[c]);
				console.log('Getting all Notifications started');
				characteristics[c].startNotifications().then(_ => {
					characteristics[c].addEventListener('characteristicvaluechanged', handleNotifications);
				});
				console.log(`${c}: ${characteristics[c]}`);
			}
		})
		.catch(error => {
			console.log('error: ' + error);
		});
}

function writeToCharacteristic(characteristic, value) {
	let bufferToSend = Int8Array.of(value);
	characteristic.writeValueWithResponse(bufferToSend)
		.then(_ => {
			//		console.log('> Characteristic changed to: ' + bufferToSend);
		})
		.catch(error => {
			log('Argh! ' + error);
		});
}

function handleNotifications(event) {
	let value = event.target.value;
	let x = value.getFloat32(0, true); // get the first 4 bytes 
	let y = value.getFloat32(4, true); // the next first 4 bytes
	let z = value.getFloat32(8, true); // the next first 4 bytes
	ax += x * 0.02 
	ay += y * 0.02; 
	az += z * 0.02; 
}

Advanced example: Remote Control robot

This advanced example allows you to control two motors via a H-bridge connected to an Arduino Uno wifi rev 2 board. Note that the IMU information is available in the example, but it’s not put to any use yet.

Arduino Code:

#include <ArduinoBLE.h>
#include <Arduino_LSM6DS3.h> // the IMU used on the Uno Wifi rev 2

#define MOTOR_PIN_1A 10
#define MOTOR_PIN_1B 9
#define MOTOR_PIN_2A 7
#define MOTOR_PIN_2B 8
#define MOTOR_PIN_1EN 6
#define MOTOR_PIN_2EN 5

int motor1Speed = 0;
int motor2Speed = 0;


BLEService robotService("19B10000-E8F2-537E-4F6C-D104768A1214"); // create service

// create characteristics and allow remote device to read and write
BLEByteCharacteristic motor1SpeedCharacteristic("19B10001-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
BLEByteCharacteristic motor2SpeedCharacteristic("19B10012-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
BLEBoolCharacteristic motor1DirectionCharacteristic("19B10013-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
BLEBoolCharacteristic motor2DirectionCharacteristic("19B10014-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
// optional IMU information
BLECharacteristic accelerationCharacteristic ("19B10014-E8F2-537E-4F6C-D104768A1214", BLENotify, sizeof(float) * 3);



void setup() {
  Serial.begin(9600);
  delay(100);

  // begin initialization
  if (!BLE.begin()) {
    Serial.println("starting BLE failed!");
    while (1);
  }

  if (!IMU.begin()) {
    Serial.println("Failed to initialize IMU!");
    while (1);
  }


  // set the local name peripheral advertises
  BLE.setLocalName("braitenbergOne");
  BLE.setDeviceName("braitenbergOne");
  // set the UUID for the service this peripheral advertises:
  BLE.setAdvertisedService(robotService);

  // add the characteristics to the service
  robotService.addCharacteristic(motor1SpeedCharacteristic);
  robotService.addCharacteristic(motor2SpeedCharacteristic);
  robotService.addCharacteristic(motor1DirectionCharacteristic);
  robotService.addCharacteristic(motor2DirectionCharacteristic);
  robotService.addCharacteristic(accelerationCharacteristic);

  // add the service
  BLE.addService(robotService);

  // start advertising
  BLE.advertise();

  Serial.println("Bluetooth device active, waiting for connections...");

  pinMode(MOTOR_PIN_1A, OUTPUT);
  pinMode(MOTOR_PIN_1B, OUTPUT);
  pinMode(MOTOR_PIN_2A, OUTPUT);
  pinMode(MOTOR_PIN_2B, OUTPUT);

  // set initial direction and speed
  digitalWrite(MOTOR_PIN_1A, HIGH);
  digitalWrite(MOTOR_PIN_1B, LOW);
  digitalWrite(MOTOR_PIN_2A, HIGH);
  digitalWrite(MOTOR_PIN_2B, LOW);
  analogWrite(MOTOR_PIN_1EN, 0);
  analogWrite(MOTOR_PIN_2EN, 0);
}

void loop() {
  // listen for BLE peripherals to connect:
  BLEDevice central = BLE.central();
  // if a central is connected to peripheral:
  if (central) {
    Serial.print("Connected to central: ");
    // print the central MAC address:
    Serial.println(central.address());
    // while the central is still connected to peripheral:

    while (central.connected()) {
      // note: we will stay in this loop as long as we are connected via BLE!
      // speed
      if (motor1SpeedCharacteristic.written()) {
        // update motor speed
        int newValue;
        newValue = motor1SpeedCharacteristic.value();
        Serial.print("motor1 : ");
        Serial.println(newValue);
        analogWrite(MOTOR_PIN_1EN, abs(newValue));
      }
      if (motor2SpeedCharacteristic.written()) {
        // update motor speeds
        int newValue;
        newValue = motor2SpeedCharacteristic.value();
        Serial.print("motor2 : ");
        Serial.println(newValue);
        analogWrite(MOTOR_PIN_2EN, abs(newValue));
      }
      // direction
      if (motor1DirectionCharacteristic.written()) {
        // update motor speeds
        bool newValue;
        newValue = motor1DirectionCharacteristic.value();
        Serial.print("motor1 Direction: ");
        Serial.println(newValue);
        if (newValue == 1) {
          digitalWrite(MOTOR_PIN_1A, HIGH);
          digitalWrite(MOTOR_PIN_1B, LOW);
        } else {
          digitalWrite(MOTOR_PIN_1A, LOW);
          digitalWrite(MOTOR_PIN_1B, HIGH);
        }

      }
      if (motor2DirectionCharacteristic.written()) {
        // update motor speeds
        bool newValue;
        newValue = motor2DirectionCharacteristic.value();
        Serial.print("motor1 Direction: ");
        Serial.println(newValue);
        if (newValue == 1) {
          digitalWrite(MOTOR_PIN_2A, HIGH);
          digitalWrite(MOTOR_PIN_2B, LOW);
        } else {
          digitalWrite(MOTOR_PIN_2A, LOW);
          digitalWrite(MOTOR_PIN_2B, HIGH);
        }
      }
      // code for making the IMU data available over bluetooth
      if (accelerationCharacteristic.subscribed() && IMU.accelerationAvailable()) {
        float acceleration[3];
        // x, y, z
        IMU.readAcceleration(acceleration[0], acceleration[1], acceleration[2]);
        accelerationCharacteristic.writeValue(acceleration, sizeof(acceleration));
      }
    }
  }
}

P5.js Code

let bleConnected = false;
const serviceUuid = "19b10000-e8f2-537e-4f6c-d104768a1214";
let myCharacteristics = [];

let point;
let speed1 = 0.0;
let speed2 = 0.0;
let lastBLEWrite = 0;

function setup() {
	createCanvas(800, 800);
	background(100);
	// Create a 'Connect' button
	const connectButton = createButton('Connect')
	connectButton.mousePressed(connectToBle);
	connectButton.position(20, 20);
	textSize(20);
	noStroke();
}

function draw() {
	if (keyIsDown(65)) { // a
		speed1 += 0.02;
	} else if (keyIsDown(81)) { // Q 
		speed1 -= 0.02;
	} else {
		speed1 -= speed1 * 0.04
	}
	if (keyIsDown(83)) { // s
		speed2 += 0.02;
	} else if (keyIsDown(87)) { // w 
		speed2 -= 0.02;
	} else {
		speed2 -= speed2 * 0.04
	}
	speed1 = constrain(speed1, -1.0, 1.0);
	speed2 = constrain(speed2, -1.0, 1.0);

	if (bleConnected) {
		writeToBle(speed1, speed2)
	}


	// interface 
	background(100);
	translate(width / 2, height / 2);
	fill(50);

	push();
	translate(0, -height * 0.3);
	rect(-width * 0.4, 0, width * 0.1, height * 0.6)
	rect(width * 0.3, 0, width * 0.1, height * 0.6)
	pop();
	fill(255, 0, 0);
	rect(-width * 0.4, 0, width * 0.1, height * (0.3 * speed1));
	rect(width * 0.3, 0, width * 0.1, height * (0.3 * speed2))
	fill(255, 0, 0);
	text("A and Q", -width * 0.25, 0);
	text("W and S", width * 0.15, 0);
}


function writeToBle(speed1, speed2) {
	if (millis() - lastBLEWrite > 50) { // limit BLE write to once every 50 miliseconds
		lastBLEWrite = millis()
		let direction1 = 0;
		let direction2 = 0;

		if (speed1 >= 0) {
			direction1 = 1
		}

		if (speed2 >= 0) {
			direction2 = 1
		}

		let speed1Byte = abs(floor(speed1 * 255))
		let speed2Byte = abs(floor(speed2 * 255))

		writeToCharacteristic(myCharacteristics[0], speed1Byte)
		writeToCharacteristic(myCharacteristics[1], speed2Byte)
		writeToCharacteristic(myCharacteristics[2], direction1)
		writeToCharacteristic(myCharacteristics[3], direction2)
	}
}


function connectToBle() {
	log('Requesting Bluetooth Device...');
	navigator.bluetooth.requestDevice({
			filters: [{
				services: [serviceUuid]
			}]
		})
		.then(device => {
			console.log('Connecting to GATT Server...');
			return device.gatt.connect();
		})
		.then(server => {
			console.log('Getting Service...');
			return server.getPrimaryService(serviceUuid);
		})
		.then(service => {
			bleConnected = true;
			console.log('Getting all Characteristics...');
			return service.getCharacteristics();
		})
		.then(characteristics => {
			for (const c in characteristics) {
					myCharacteristics.push(characteristics[c]);
			
				console.log('> Notifications started');
				characteristics[c].startNotifications().then(_ => {
					characteristics[c].addEventListener('characteristicvaluechanged', handleNotifications);
				}); 
	
				console.log(`${c}: ${characteristics[c]}`);
			}


		})
		.catch(error => {
			console.log('error: ' + error);
		});
}

function writeToCharacteristic(characteristic, value) {
	let bufferToSend = Int8Array.of(value);
	characteristic.writeValueWithResponse(bufferToSend)
		.then(_ => {
			//		console.log('> Characteristic changed to: ' + bufferToSend);
		})
		.catch(error => {
			log('Argh! ' + error);
		});
}

function handleNotifications(event) {
	let value = event.target.value;
	ax = value.getFloat32(0, true);
    ay = value.getFloat32(4, true);
    az = value.getFloat32(8, true);
//	console.log('ax> ' + ax +'ay> ' + ay +'az> ' + az);
}

Advanced example 2: Lynx Smart Servo

This example is similar to the previous one, but it makes use of the Lynx Smart Servo instead of the DC-Motors, again using the Arduino Uno wifi rev 2 board.

Arduino Code:

#include <ArduinoBLE.h>
#include <Arduino_LSM6DS3.h> // the IMU used on the Uno Wifi rev 2
#include <SoftwareSerial.h>

SoftwareSerial mySerial(8, 9); // Create the new software serial instance

BLEService robotService("19B10000-E8F2-537E-4F6C-D104768A1214"); // create service

// create characteristics and allow remote device to read and write
BLEIntCharacteristic motor1SpeedCharacteristic("19B10001-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
BLEIntCharacteristic motor2SpeedCharacteristic("19B10012-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
// optional IMU information
BLECharacteristic accelerationCharacteristic ("19B10014-E8F2-537E-4F6C-D104768A1214", BLENotify, sizeof(float) * 3);


void setup() {
  Serial.begin(9600);
  delay(100);

  // begin initialization
  if (!BLE.begin()) {
    Serial.println("starting BLE failed!");
    while (1);
  }

  if (!IMU.begin()) {
    Serial.println("Failed to initialize IMU!");
    while (1);
  }


  // set the local name peripheral advertises
  BLE.setLocalName("braitenbergOne");
  BLE.setDeviceName("braitenbergOne");
  // set the UUID for the service this peripheral advertises:
  BLE.setAdvertisedService(robotService);

  // add the characteristics to the service
  robotService.addCharacteristic(motor1SpeedCharacteristic);
  robotService.addCharacteristic(motor2SpeedCharacteristic);
  robotService.addCharacteristic(accelerationCharacteristic);

  // add the service
  BLE.addService(robotService);

  // start advertising
  BLE.advertise();

  Serial.println("Bluetooth device active, waiting for connections...");

// 
  mySerial.begin(115200); // Important! this is the standard speed for talking to LSS
  mySerial.print("#0D1500\r");  // this is used to clear the serial buffer
  mySerial.print(String("#") + 2 + String("WR") + 0 + "\r"); // RPM move, set to 0
  mySerial.print(String("#") + 1 + String("WR") + 0 + "\r"); // RPM move, set to 0

}

void loop() {
  // listen for BLE peripherals to connect:
  BLEDevice central = BLE.central();
  // if a central is connected to peripheral:
  if (central) {
    Serial.print("Connected to central: ");
    // print the central MAC address:
    Serial.println(central.address());
    // while the central is still connected to peripheral:

    while (central.connected()) {
      // note: we will stay in this loop as long as we are connected via BLE!
      // speed
      if (motor1SpeedCharacteristic.written()) {
        // update motor speed
        int newValue;
        newValue = motor1SpeedCharacteristic.value();
        Serial.print("motor1 : ");
        Serial.println(newValue);
        // motor direction 
        mySerial.print(String("#") + 2 + String("WR") + newValue + "\r"); // RPM move
      }
      if (motor2SpeedCharacteristic.written()) {
        // update motor speeds
        int newValue;
        newValue = motor2SpeedCharacteristic.value();
        Serial.print("motor2 : ");
        Serial.println(-newValue);
        mySerial.print(String("#") + 1 + String("WR") + -newValue + "\r"); // RPM move
      }
      // code for making the IMU data available over bluetooth
      if (accelerationCharacteristic.subscribed() && IMU.accelerationAvailable()) {
        float acceleration[3];
        // x, y, z
        IMU.readAcceleration(acceleration[0], acceleration[1], acceleration[2]);
        accelerationCharacteristic.writeValue(acceleration, sizeof(acceleration));
      }
    }
  }
}

P5.js Code

let bleConnected = false;
const serviceUuid = "19b10000-e8f2-537e-4f6c-d104768a1214";
let myCharacteristics = [];

let point;
let speed1 = 0.0;
let speed2 = 0.0;
let lastBLEWrite = 0;

// IMU DATA

let ax = 0;
let ay= 0;
let az= 0;

function setup() {
	createCanvas(800, 800);
	background(100);
	// Create a 'Connect' button
	const connectButton = createButton('Connect')
	connectButton.mousePressed(connectToBle);
	connectButton.position(20, 20);
	textSize(20);
	noStroke();
}

function draw() {
	if (keyIsDown(65)) { // a
		speed1 += 0.02;
	} else if (keyIsDown(81)) { // Q 
		speed1 -= 0.02;
	} else {
		speed1 -= speed1 * 0.04
	}
	if (keyIsDown(83)) { // s
		speed2 += 0.02;
	} else if (keyIsDown(87)) { // w 
		speed2 -= 0.02;
	} else {
		speed2 -= speed2 * 0.04
	}
	speed1 = constrain(speed1, -1.0, 1.0);
	speed2 = constrain(speed2, -1.0, 1.0);

	if (bleConnected) {
		writeToBle(speed1, speed2)
	}

	// interface 
	background(100);
	translate(width / 2, height / 2);
	fill(50);

	push();
	// grey bars 
	translate(0, -height * 0.3);
	rect(-width * 0.4, 0, width * 0.1, height * 0.6)
	rect(width * 0.3, 0, width * 0.1, height * 0.6)
	pop();
	// red bars for speed
	fill(255, 0, 255);
	rect(-width * 0.4, 0, width * 0.1, height * (0.3 * speed1));
	rect(width * 0.3, 0, width * 0.1, height * (0.3 * speed2))
	fill(255, 0, 255);
	text("A and Q", -width * 0.25, 0);
	text("W and S", width * 0.15, 0);
	
	// imu visual 
	fill(255, 255, 0);
	push();
	translate(-40,0);
	rect(0, 0, 10, -100 * ax)
	rect(30, 0, 10, -100 * ay)
	rect(60, 0, 10, -100 * az)
	textSize(10);
	text("X", -10, 0);
	text("Y", 20, 0);
	text("Z", 50, 0);
	pop();
	
}

function writeToBle(speed1, speed2) {
	if (millis() - lastBLEWrite > 50) { // limit BLE write to once every 50 miliseconds
		lastBLEWrite = millis()

		let speed1Int = floor(speed1 * 50)
		let speed2Int = floor(speed2 * 50)
		writeToCharacteristic(myCharacteristics[0], speed1Int)
		writeToCharacteristic(myCharacteristics[1], speed2Int)
	}
}

function connectToBle() {
	log('Requesting Bluetooth Device...');
	navigator.bluetooth.requestDevice({
			filters: [{
				services: [serviceUuid]
			}]
		})
		.then(device => {
			console.log('Connecting to GATT Server...');
			return device.gatt.connect();
		})
		.then(server => {
			console.log('Getting Service...');
			return server.getPrimaryService(serviceUuid);
		})
		.then(service => {
			bleConnected = true;
			console.log('Getting all Characteristics...');
			return service.getCharacteristics();
		})
		.then(characteristics => {
			for (const c in characteristics) {
					myCharacteristics.push(characteristics[c]);
			
				console.log('> Notifications started');
				characteristics[c].startNotifications().then(_ => {
					characteristics[c].addEventListener('characteristicvaluechanged', handleNotifications);
				}); 
				console.log(`${c}: ${characteristics[c]}`);
			}

		})
		.catch(error => {
			console.log('error: ' + error);
		});
}

function writeToCharacteristic(characteristic, value) {
	let bufferToSend = Int16Array.of(value); // note, arduino uses 16 bits for integer. This is important since the 1st bit in a signed integer is used for +/-, which will result in a changed in value if we convert from one size int to another!
	characteristic.writeValueWithResponse(bufferToSend)
		.then(_ => {
			//		console.log('> Characteristic changed to: ' + bufferToSend);
		})
		.catch(error => {
			log('Argh! ' + error);
		});
}

function handleNotifications(event) {
	let value = event.target.value;
	ax = value.getFloat32(0, true); // arduino uses 4 bytes for each float. Here we split the dataview object into 4 values
    ay = value.getFloat32(4, true);
    az = value.getFloat32(8, true);
	//console.log('ax> ' + ax +'ay> ' + ay +'az> ' + az);
}