After some research into the different Bluetooth modules and their capabilities, I was able to focus on my next goal: Using Bluetooth for the remote control with the joystick shield that has been expanded with an LCD display.
The communication from the joystick shield is compatible with the ArduinoBlue software library used in the model to be controlled. This makes control with the joystick shield interchangeable with the ArduinoBlue app without having to change the Sketch in the cart.
As a controllable model I use the little car from the book "fischertechnik-Roboter mit Arduino" by Dirk Fox and Thomas Püttmann. In the section 'Model variants' on the accompanying site to this book is a Sketch for the car that makes it controllable by the ArduinoBlue app which is available for both iOS and Android devices. The control Sketch of the car, the 'Flitzer', uses the ArduinoBlue software library for the Arduino.
This ArduinoBlue app also has a 'virtual joystick' on the smartphone screen that can be used to control. But since I was already quite far with making the joystick shield usable for remote control, it seemed like a nice challenge to make it compatible with this. In this way, the car can be controlled either with the app or with this self-built physical joystick unit.
To do this, communication between two Bluetooth (BLE) modules must be established and the joystick shield must be equipped with a module that has the 'Central', or 'Controller' role. This can then automatically connect to the module with 'Peripheral' role in the model to be controlled. I describe this part of the experiment in the previous project.
However, data traffic in the example on the aforementioned website is only one-way. I thought it would be nice to be able to communicate back to the joystick shield, so that messages or measured values from the controllable model could be shown on a display on the unit.
The joystick shield already has a connector for connecting a Nokia5110 display, but because I wanted to build a case for it, a 2-line LCD display that can be controlled via the I²C bus seemed more practical in the end.
For the communication between the Arduino and the Bluetooth module, the use of SoftwareSerial in the Sketch is obvious. This means that the serial communication does not have to take place over the hardware serial on D0 and D1, which are also used for the USB with which the Arduino is connected to the computer. This has the great advantage that the module does not have to be temporarily removed when a new Sketch is uploaded to the Arduino. In addition, the serial monitor of the Arduino IDE remains usable during development.
But unfortunately this turned out not to be possible because the servo library uses the same Arduino hardware timer for controlling the control servo as SoftwareSerial for its outgoing signals to the module.
Especially when sending via the RxD input of the module, the result may be interference on the servo steering, sometimes causing violent servo jitter. I therefore chose to connect the module to the regular hardware serial on D0 and D1 and just unplug it during an occasional upload.
Below the connection diagram for the motor shield. I made (just to be sure) a so-called level shifter with two resistors for the RxD of the module.
// 'Flitzer' with Bluetooth remote joystick shield
// ArduinoBlue compatible, uses Adafruit AdaFruit MotorShield
//
// Arnoud van Delden - March 2021
// Because PWM pins 9 and 10 use timer1, there is a conflict in using Software Serial
// This version uses the normal hardware RX/TX pins 0 and 1. Unplug the BT module during debug or upload!
// In my case: YELLOW wire to (output) TxD of BT module connects to pin 0 (RxD input) of the Arduino
// In my case: GREEN wire with level-shifter to (input) RxD of BT module connects to pin 1 (TxD output) of the Arduino
//
#include "Servo.h"
#include "Adafruit_MotorShield.h"
#include "ArduinoBlue.h"
//#define DEBUG
//#define BTBaud 38400 // Did some experiments on 38400 baud...
#define BTBaud 9600 // Configured/leaved my MT-19 BLE at 9600 baud...
// Various defines...
#define EncoderIRQPin 2
#define ServoPin 9
#define HornPin 12
#define minAngle 55
#define maxAngle 125
#define MaxSpeed 255
#define FlasherL 0
#define FlasherR 14
#define REARLIGHT 100 // Default read light brightness, with headroom for brake light (=255)
// Distance and velocity measurement...
//#define IPCM 14.475 // Theoretical nr impulses per cm with 50mm wheels...
#define IPCM 17.949 // My own value, derived from experiment and measure...
#define Interval 1000 // Sample/Measure interval in ms
volatile unsigned long tachoPulses;
unsigned long starttime;
const float f = 36000/IPCM; // Speed m/h = f x Impulses / Interval
unsigned long tachoSample;
float velocity, distance; // Speed & Distance
float velocityAvg; // Average speed
unsigned long tachoTimer;
char valueStr[15];
char displayStr[50];
ArduinoBlue remoteBLE(Serial); // BLE over RX/TX hardware serial!
Servo ServoMotor; // Steering servo...
Adafruit_MotorShield MShield = Adafruit_MotorShield(0x60);
Adafruit_DCMotor *Motor = MShield.getMotor(1); // Main motor
Adafruit_DCMotor *Light = MShield.getMotor(2); // Headlights...
Adafruit_DCMotor *RedRearLight = MShield.getMotor(3); // Rear and brake light...
Adafruit_DCMotor *ReverseLight = MShield.getMotor(4); // Reverse light..
int error = 0;
byte controller_type = 0;
int motorspeed = 0;
int lastspeed = 0;
int steerAngle = 90; // Start with default steer angle...
unsigned long lasttime;
unsigned long brakeOffTimer;
boolean FlasherLeft = false, FlasherRight = false, FlasherOn = false, RumbleBrake = false,
WarningLights = false, BrakeLights = false, autoParking = false, lightsOn = false;
boolean showSpeed = false;
// Vars for ArduinoBlue...
int throttleAB, steeringAB, buttonAB; // Sliders are not used (yet)...
void count() { // Interrupt routine of encoder motor...
tachoPulses++;
}
void driveCar() { // Remote controlled car...
throttleAB = abs(remoteBLE.getThrottle());
steeringAB = abs(remoteBLE.getSteering());
if (steeringAB>99) steeringAB = 99;
buttonAB = remoteBLE.getButton();
// Servo steering...
steerAngle = map(steeringAB, 0, 100, minAngle, maxAngle);
#ifdef DEBUG
if (steerAngle != 90) {
Serial.print(" steerAngle: ");
Serial.println(steerAngle, DEC);
}
#endif
ServoMotor.write(steerAngle);
// Process and set motor speed...
motorspeed = throttleAB - 50;
if (motorspeed>0) {
// Forward...
//motorspeed = abs(motorspeed);
motorspeed = map(motorspeed, 0, 50, 0, 255);
Motor->setSpeed(motorspeed);
Motor->run(FORWARD);
ReverseLight->setSpeed(0);
#ifdef DEBUG
if (motorspeed>0) {
Serial.print("Forward motorspeed: ");
Serial.println(motorspeed, DEC);
}
#endif
} else {
// Backward/reverse...
motorspeed = map(motorspeed, 0, -50, 0, 255);
Motor->run(BACKWARD);
Motor->setSpeed(motorspeed);
if (motorspeed>5)
ReverseLight->setSpeed(255);
else // Switch off reverse light if not moving...
ReverseLight->setSpeed(0);
#ifdef DEBUG
if (motorspeed>0) {
Serial.print("Reverse motorspeed: ");
Serial.println(motorspeed, DEC);
}
#endif
}
if (motorspeed0) {
delay(100); // Delay for button debouncing
// Car horn...
if (buttonAB==4) { // Button 4 was pressed...
tone(HornPin, 200, 500);
delay(1000);
tone(HornPin, 200, 500);
delay(500);
noTone(HornPin);
#ifdef DEBUG
Serial.println("Horn sounded");
#endif
}
// Toggle head and rear lights...
if (buttonAB==1) { // Button 1 was pressed...
if (lightsOn) {
Light->setSpeed(0);
RedRearLight->setSpeed(0);
lightsOn=false;
} else {
Light->setSpeed(255);
RedRearLight->setSpeed(REARLIGHT);
lightsOn=true;
}
#ifdef DEBUG
Serial.println("Headlights toggle");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
// Toggle warning lights...
if (buttonAB==2) { // Button 2 was pressed...
if (WarningLights)
WarningLights = false;
else
WarningLights = true;
#ifdef DEBUG
Serial.println("WarningLights toggle");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
// Reset speed and distance...
if (buttonAB==3) { // Button 3 was pressed...
tachoPulses = tachoSample = 0;
distance = velocity = velocityAvg = 0.0;
#ifdef DEBUG
Serial.println("Reset speed and distance");
#endif
}
// showSpeed...
if (buttonAB==5) { // Button 5 was pressed...
if (showSpeed) { // End display mode...
remoteBLE.sendMessage("VALUES");
} else {
remoteBLE.sendMessage("CLR");
delay(100);
remoteBLE.sendMessage("LCDPRINT0,0:Speed 0.00 m/h ");
delay(100);
remoteBLE.sendMessage("LCDPRINT1,1:Dist 0.00 cm ");
delay(100);
}
//delay(100);
showSpeed = !showSpeed;
#ifdef DEBUG
Serial.println("Show velocity and speed");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
}
}
void setup() {
// Setup speed/distance tracking...
pinMode(EncoderIRQPin, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(EncoderIRQPin), count, CHANGE);
starttime = millis(); // Millisecs since program start...
// Initialize car horn buzzer and signal we're alive...
pinMode(HornPin, OUTPUT);
tone(HornPin, 800, 250);
delay(500);
tone(HornPin, 800, 250);
delay(250);
noTone(HornPin);
// Init BLE module over Hardware Serial...
Serial.begin(BTBaud); // Start serial monitor
MShield.begin(); // Motor Shield init...
Wire.setClock(400000); // Set I²C-Frequency to 400 kHz...
ServoMotor.attach(ServoPin); // Servo with default angle...
ServoMotor.write(steerAngle); // Default middle...
ReverseLight->setSpeed(0);
ReverseLight->run(FORWARD);
RedRearLight->setSpeed(0);
RedRearLight->run(BACKWARD);
Light->setSpeed(0);
Light->run(FORWARD);
MShield.setPin(FlasherL, false);
MShield.setPin(FlasherR, false);
tachoPulses = 0;
motorspeed = 0;
Motor->run(FORWARD); // Default=Forward...
Motor->setSpeed(motorspeed);
delay(1000);
}
void Flasher() {
if (FlasherOn) {
if (FlasherLeft) MShield.setPin(FlasherL, true);
if (FlasherRight) MShield.setPin(FlasherR, true);
}
else {
if (FlasherLeft) MShield.setPin(FlasherL, false);
if (FlasherRight) MShield.setPin(FlasherR, false);
}
FlasherOn = !FlasherOn;
}
void loop() {
// Do tacho stuff each interval, but only if showSpeed=true...
if (showSpeed && (millis()-tachoTimer) > Interval) {
tachoTimer = millis(); // Restart timer...
distance = tachoPulses / IPCM;
velocity = (tachoPulses-tachoSample) * f / Interval; // Recalc to impulses m/h
//velocityAvg = tachoPulses * f / (millis()-starttime);
// Format and output velocity on the remote display...
valueStr[0] = 0;
dtostrf(velocity, 3, 2, valueStr); // 3 is mininum width, 2 is precision
sprintf(displayStr, "LCDPRINT0,6:%s m/h |", valueStr);
remoteBLE.sendMessage(displayStr);
// Format and output distance on the remote display...
valueStr[0] = 0;
dtostrf(distance, 3, 2, valueStr); // 3 is mininum width, 2 is precision
sprintf(displayStr, "LCDPRINT1,6:%s cm |", valueStr);
remoteBLE.sendMessage(displayStr);
tachoSample = tachoPulses; // Store current count...
}
if (autoParking) { // auto parking...
// To Do...
autoParking = false; // End parking procedure...
} else {
// Normal loop...
driveCar(); // Main...
// Write distance and speed to remote display...
if (WarningLights) { // Flashers on...
FlasherRight = true;
FlasherLeft = true;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else { // Flashers off...
if (steerAngle < 89) { // Steering left
FlasherLeft = true;
FlasherRight = false;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else if (steerAngle > 91) { // Steering right
FlasherRight = true;
FlasherLeft = false;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else {
FlasherRight = false;
FlasherLeft = false;
MShield.setPin(FlasherL, false); // Left flasher off
MShield.setPin(FlasherR, false); // Right flasher off
FlasherOn = false;
}
}
// Brake light handling and auto-off...
if (BrakeLights) {
if (brakeOffTimer <= 0) brakeOffTimer = millis(); // Start timer...
if ((millis()-brakeOffTimer) > 1000) { // Time-out brake lights...
BrakeLights = false;
brakeOffTimer = 0;
} else {
RedRearLight->setSpeed(255);
}
} else {
if (lightsOn)
RedRearLight->setSpeed(REARLIGHT);
else
RedRearLight->setSpeed(0);
}
}
}
The joystick shield already has an I²C bus connector for the LCD display at the bottom right, and a connector at the top right for connecting a Bluetooth module. The signal levels and supply voltage are already 3.3 volts so no additional level shifter needs to be made. The outer 2 pins of the Bluetooth module fall next to the socket because it only carries the four necessary connections. However, I removed these connectors because I wanted to put the necessary connections neatly under the PCB. In this way they don't get in the way of the buttons either.
A piezo buzzer on the remote unit seemed useful to me. For example to pass an alarm from the model. I connected it to input A3. Because I wanted to show the connection status of the module as an icon on the display, I connected the STATE pin to input A4.
The outgoing control signals from the joystick shield are compatible with the ArduinoBlue library. For the display I built in my own command set with which the model can display, blink or delete texts on it.
// 'Flitzer' with Bluetooth remote joystick shield
// ArduinoBlue compatible, uses Adafruit AdaFruit MotorShield
//
// Arnoud van Delden - February-March 2021
//
#include "Servo.h"
#include "Adafruit_MotorShield.h"
#include "SoftwareSerial.h"
#include "ArduinoBlue.h"
//#define DEBUG
#define Baudrate 38400 // Serial monitor during DEBUG mode...
// Various defines...
#define EncoderIRQPin 2
#define ServoPin 9
#define HornPin 12
#define minAngle 55
#define maxAngle 125
#define MaxSpeed 255
#define FlasherL 0
#define FlasherR 14
#define REARLIGHT 100 // Default read light brightness, with headroom for brake light (=255)
// Distance and velocity measurement...
#define IPCM 14.606 // Nr impulses per cm with 50mm wheels...
#define Interval 1000 // Sample-/Measure interval in ms
volatile unsigned long tachoPulses;
unsigned long starttime;
const float f = 36000/IPCM; // Geschw. m/h = f x Impulse / Interval
unsigned long tachoSample;
float velocity, velocityAvg, distance;
unsigned long tachoTimer;
char valueStr[15];
char displayStr[50];
// Software Serial for BT-module. Keep D9 and D10 free on the otorshield for servos!
#define RX 4
#define TX 5
#define GND 6
#define Vcc 7
//#define BTBaud 38400 // Configured my MT-19 BLE to 38400 baud...
#define BTBaud 9600 // Configured my MT-19 BLE to 9600 baud...
SoftwareSerial BT(TX, RX);
ArduinoBlue remoteBLE(BT);
Servo ServoMotor; // Steering servo...
Adafruit_MotorShield MShield = Adafruit_MotorShield(0x60);
Adafruit_DCMotor *Motor = MShield.getMotor(1); // Main motor
Adafruit_DCMotor *Light = MShield.getMotor(2); // Headlights...
Adafruit_DCMotor *RedRearLight = MShield.getMotor(3); // Rear and brake light...
Adafruit_DCMotor *ReverseLight = MShield.getMotor(4); // Reverse light..
int error = 0;
byte controller_type = 0;
int motorspeed = 0;
int lastspeed = 0;
int steerAngle = 90; // Start with default steer angle...
unsigned long lasttime;
unsigned long brakeOffTimer;
boolean FlasherLeft = false, FlasherRight = false, FlasherOn = false, RumbleBrake = false,
WarningLights = false, BrakeLights = false, autoParking = false, lightsOn = false;
boolean showSpeed = true;
// Vars for ArduinoBlue...
int throttleAB, steeringAB, buttonAB; // Sliders are not used (yet)...
void count() { // Interrupt routine of encoder motor...
tachoPulses++;
}
void driveCar() { // Remote controlled car...
throttleAB = abs(remoteBLE.getThrottle());
steeringAB = abs(remoteBLE.getSteering());
if (steeringAB>99) steeringAB = 99;
buttonAB = remoteBLE.getButton();
// Servo steering...
steerAngle = map(steeringAB, 0, 100, minAngle, maxAngle);
#ifdef DEBUG
if (steerAngle != 90) {
Serial.print(" steerAngle: ");
Serial.println(steerAngle, DEC);
}
#endif
ServoMotor.write(steerAngle);
// Process and set motor speed...
motorspeed = throttleAB - 50;
if (motorspeed>0) {
// Forward...
//motorspeed = abs(motorspeed);
motorspeed = map(motorspeed, 0, 50, 0, 255);
Motor->setSpeed(motorspeed);
Motor->run(FORWARD);
ReverseLight->setSpeed(0);
#ifdef DEBUG¨
if (motorspeed>0) {
Serial.print("Forward motorspeed: ");
Serial.println(motorspeed, DEC);
}
#endif
} else {
// Backward/reverse...
motorspeed = map(motorspeed, 0, -50, 0, 255);
Motor->run(BACKWARD);
Motor->setSpeed(motorspeed);
if (motorspeed>5)
ReverseLight->setSpeed(255);
else // Switch off reverse light if not moving...
ReverseLight->setSpeed(0);
#ifdef DEBUG
if (motorspeed>0) {
Serial.print("Reverse motorspeed: ");
Serial.println(motorspeed, DEC);
}
#endif
}
if (motorspeed0) {
delay(100); // Delay for button debouncing
// Car horn...
if (buttonAB==4) { // Button 4 was pressed...
tone(HornPin, 200, 500);
delay(1000);
tone(HornPin, 200, 500);
delay(500);
noTone(HornPin);
#ifdef DEBUG
Serial.println("Horn sounded");
#endif
}
// Toggle head and rear lights...
if (buttonAB==1) { // Button 1 was pressed...
if (lightsOn) {
Light->setSpeed(0);
RedRearLight->setSpeed(0);
lightsOn=false;
} else {
Light->setSpeed(255);
RedRearLight->setSpeed(REARLIGHT);
lightsOn=true;
}
#ifdef DEBUG
Serial.println("Headlights toggle");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
// Toggle warning lights...
if (buttonAB==2) { // Button 2 was pressed...
if (WarningLights)
WarningLights = false;
else
WarningLights = true;
#ifdef DEBUG
Serial.println("WarningLights toggle");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
// Reset speed and distance...
if (buttonAB==3) { // Button 3 was pressed...
tachoPulses = tachoSample = 0;
distance = velocity = velocityAvg = 0.0;
Serial.println("Reset speed and distance");
#ifdef DEBUG
Serial.println("Reset speed and distance");
#endif
}
// showSpeed...
if (buttonAB==5) { // Button 5 was pressed...
if (showSpeed) { // End display mode...
remoteBLE.sendMessage("VALUES");
} else {
remoteBLE.sendMessage("CLR");
delay(100);
remoteBLE.sendMessage("LCDPRINT0,0:Speed m/h");
delay(100);
remoteBLE.sendMessage("LCDPRINT1,1:Dist cm");
delay(100);
}
showSpeed = !showSpeed;
#ifdef DEBUG
Serial.println("Show velocity and speed");
#endif
// Toggle buttons/functions are one-shot, so wait until button is released
while (remoteBLE.getButton()>0) delay(100);
}
}
//delay(50); // Grace...
}
void setup() {
#ifdef DEBUG
Serial.begin(Baudrate); // Start serial monitor
#endif
// Setup speed/distance tracking...
pinMode(EncoderIRQPin, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(EncoderIRQPin), count, CHANGE);
starttime = millis(); // Millisecs since program start...
// Initialize car horn buzzer and signal we're alive...
pinMode(HornPin, OUTPUT);
tone(HornPin, 800, 250);
delay(500);
tone(HornPin, 800, 250);
delay(250);
noTone(HornPin);
// Init BLE module over Software Serial...
BT.begin(BTBaud);
delay(1000);
MShield.begin(); // Motor Shield init...
Wire.setClock(400000); // Set I²C-Frequency to 400 kHz...
ServoMotor.attach(ServoPin); // Servo with default angle...
ServoMotor.write(steerAngle); // Default middle...
ReverseLight->setSpeed(0);
ReverseLight->run(FORWARD);
RedRearLight->setSpeed(0);
RedRearLight->run(BACKWARD);
Light->setSpeed(0);
Light->run(FORWARD);
MShield.setPin(FlasherL, false);
MShield.setPin(FlasherR, false);
tachoPulses = 0;
motorspeed = 0;
Motor->run(FORWARD); // Default=Forward...
Motor->setSpeed(motorspeed);
delay(1000);
}
void Flasher() {
if (FlasherOn) {
if (FlasherLeft) MShield.setPin(FlasherL, true);
if (FlasherRight) MShield.setPin(FlasherR, true);
}
else {
if (FlasherLeft) MShield.setPin(FlasherL, false);
if (FlasherRight) MShield.setPin(FlasherR, false);
}
FlasherOn = !FlasherOn;
}
void loop() {
// Do tacho stuff each interval, but only if showSpeed=true...
if (showSpeed && (millis() - tachoTimer) > Interval) {
tachoTimer = millis(); // Restart timer...
distance = tachoPulses / IPCM;
velocity = (tachoPulses-tachoSample) * f / Interval; // Recalc to impulses m/h
velocityAvg = tachoPulses * f / (millis()-starttime);
#ifdef DEBUG
Serial.print("distance=");
Serial.println(distance);
dtostrf(distance, 3, 2, valueStr); // 3 is mininum width, 2 is precision
sprintf(displayStr, "distance %s cm", valueStr);
Serial.println(displayStr);
Serial.print("velocity=");
Serial.println(velocity);
dtostrf(velocity, 3, 2, valueStr); // 3 is mininum width, 2 is precision
sprintf(displayStr, "velocity %s m/h", valueStr);
Serial.println(displayStr);
//Serial.print("velocityAvg=");
//Serial.println(velocityAvg);
#endif
tachoSample = tachoPulses; // Store current count...
}
if (autoParking) { // auto parking...
// To Do...
autoParking = false; // End parking procedure...
} else {
// Normal loop...
driveCar(); // Main...
// Write distance and speed to remote display...
if (WarningLights) { // Flashers on...
FlasherRight = true;
FlasherLeft = true;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else { // Flashers off...
if (steerAngle < 89) { // Steering left
FlasherLeft = true;
FlasherRight = false;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else if (steerAngle > 91) { // Steering right
FlasherRight = true;
FlasherLeft = false;
if ((millis()-lasttime) > 500) { // Flasher routine
lasttime = millis();
Flasher();
}
}
else {
FlasherRight = false;
FlasherLeft = false;
MShield.setPin(FlasherL, false); // Left flasher off
MShield.setPin(FlasherR, false); // Right flasher off
FlasherOn = false;
}
}
// Brake light handling and auto-off...
if (BrakeLights) {
if (brakeOffTimer <= 0) brakeOffTimer = millis(); // Start timer...
if ((millis()-brakeOffTimer) > 1000) { // Time-out brake lights...
BrakeLights = false;
brakeOffTimer = 0;
} else {
RedRearLight->setSpeed(255);
}
} else {
if (lightsOn)
RedRearLight->setSpeed(REARLIGHT);
else
RedRearLight->setSpeed(0);
}
}
}
When using the joystick shield with the LCD display, the model's output capabilities on the controller display are useful for functional messages or warnings. However, it makes sense to start sending continuously updated notifications, such as distance and speed of the car, only after pressing a specific button on the joystick shield. The ArduinoBlue app reports each message in a separate pop-up window and is therefore quickly overloaded.
In the Sketch above I used the small smd button 'F' on the joystick shield for this purpose. By pressing again you will return to the display of the joystick and button values. It also turned out to be useful in practice to be able to reset the distance traveled. This is possible with button 'C'.
The ArduinoBlue app on the smartphone connects with the factory settings directly with the Bluetooth module in the model. Because the ArduinoBlue function library is used in the Sketch for the controllable model, it can be controlled with the ArduinoBlue app or this self-made unit, depending on which control is connected to the cart. Although, only one control can be active at a time, of course.