Showing posts with label robot. Show all posts
Showing posts with label robot. Show all posts

November 01, 2024

Arduino balancing bot



I built an Arduino version of the balancing bot from old parts in my parts bin:
  • Arduino Mega2560
  • Motor Shield V1
  • 3v-to-5v level converter
  • MPU-9255
  • toy DC motors and wheels
  • 9V battery holder for Arduino
  • 4x AA battery holder for the motors

The Motor Shield V1 is really obsolete. The I2C pins are not passed through. That makes using it with the Arduino UNO impossible. So I switched to the Mega2560 that has the I2C pins duplicated at a different location. The 3.3v pin is still not passed through. That got fixed with a Dremel. The L293D chip on the motor shield is really inefficient and the voltage drop is significant.

There is a newer Motor Shield V2 without any of these problems. But I didn't want to spend $20. In addition, the new version uses I2C and I didn't feel like troubleshooting multiple devices on the I2C bus with a level converter.

The Arduino UNO R3 and to some extent the Mega2560 are obsolete too. The new Arduino UNO R4 has a far more efficient switching regulator, LED matrix display, and optional bluetooth and wifi support.

The MPU-9255 has been out of production for years.

The 3v-to-5v level converter is needed because the Arduino is a 5v device and the MPU-9255 is a 3v device. You really want to respect the voltages when it comes to I2C communications.

Connecting it all up is easy, right? Just add a few more power and ground pins on the motor shield and use wires with DuPont connectors:


Actually, no. 

DuPont connectors do not connect securely. Whenever the bot falls, some wires risk coming loose. Cheap pre-made wires with DuPont connectors also fail at an alarmingly high rate. 

Well, I found an alternative:


Wire wrapping to the rescue! Those tiny white wires are 30 AWG Kynar wire wrapping wires. You can wire wrap any rectangular post that is small enough to fit the wire wrapping tool. You can wire wrap DuPont pins! For female headers, wire wrap one side of a double male header and plug it in.

Wire wrapping is actually more secure than soldering. It is also easier to wrap or unwrap than to solder or de-solder. The Cray 1 was wire wrapped. That's good enough for my toy robot. It has gone out of fashion many decades ago though. Fortunately, you can still buy proper Kynar wire wrapping wires and a wire wrapping tool off your favorite online store. Get the tool that does modified wraps.

As for the code, I just ported my Javascript Microbit code to Arduino C.

The Motor Shield V1 can be controlled using the Adafruit Motor Shield library v1.0.1. That seems to work fine.

However, I couldn't find a MPU-9255 library that suited my needs. I ported my MPU-9255 code and even added accelerometer bias adjustments.

Tuning the PID parameters took a few hours. The PID scaling constants seem to depend on the mounting height of the sensor. The bot to stayed up for 2 hours before I shut it down.





Here's the code:

#include <Wire.h>
#include <AFMotor.h>

// Tuning Parameters
float TARGET_ANGLE = -3.1; // forward tilt in degrees
float SMOOTHING_FACTOR = 200;

float KE = 15;
float KD = KE/20;
float KI = KD/5;

const int MPU_ADDR = 0x68;
const int WHO_AM_I = 0x75;
const int REG_PWR_MGMT_1 = 0x6b;
const int REG_SIGNAL_PATH_RESET = 0x68;
const int REG_USER_CTRL = 0x6a;
const int REG_ACCEL_XOUT_H = 0x3b;
const int REG_ACCEL_YOUT_H = 0x3d;
const int REG_ACCEL_ZOUT_H = 0x3f;
const int REG_GYRO_XOUT_H = 0x43;
const int REG_GYRO_YOUT_H = 0x45;
const int REG_GYRO_ZOUT_H = 0x47;
const int REG_CONFIG = 0x1a;
const int REG_GYRO_CONFIG = 0x1b;
const int REG_ACCEL_CONFIG = 0x1c;
const int REG_ACCEL_CONFIG2 = 0x1d;
const int XG_OFFSET_H = 0x13;
const int YG_OFFSET_H = 0x15;
const int ZG_OFFSET_H = 0x17;
const int XA_OFFSET_H = 0x77;
const int YA_OFFSET_H = 0x7A;
const int ZA_OFFSET_H = 0x7D;

bool mpu_read(int reg, byte *data) {
Wire.beginTransmission(MPU_ADDR);
Wire.write(reg);
Wire.endTransmission(false);
int n = Wire.requestFrom(MPU_ADDR, 1);
if (n != 1) {
return false;
}
*data = Wire.read();
return true;
}

bool mpu_read_int16(int reg, short *data) {
Wire.beginTransmission(MPU_ADDR);
Wire.write(reg);
Wire.endTransmission(false);
int n = Wire.requestFrom(MPU_ADDR, 2);
if (n != 2) {
return false;
}
int h = Wire.read();
int l = Wire.read();
*data = (h << 8) | l;
return true;
}

void mpu_write(int reg, int data) {
Wire.beginTransmission(MPU_ADDR);
Wire.write(reg);
Wire.write(data & 0xff);
Wire.endTransmission();
}

void mpu_write_int16(int reg, int data) {
Wire.beginTransmission(MPU_ADDR);
Wire.write(reg);
Wire.write((data >> 8) & 0xff);
Wire.write(data & 0xff);
Wire.endTransmission();
}

/**
* Reset the MPU and configure the gyroscope to +- 2000 degrees/second and the accelerometer to +-16g.
* The low pass filter settings control how sensitive the sensors are to quick changes.
* In order of increasing sensitivity: 6, 5, 4, 3, 2, 1, 0, 7
* Info from MPU-9250 register map document.
* @param gyro_lpf Gyroscope low pass filter setting, eg: 0
* 7: 8kHz sampling rate, 3600Hz bandwidth, 0.17ms delay.
* 0: 8kHz sampling rate, 250Hz bandwidth, 0.97ms delay.
* 1: 1kHz sampling rate, 184Hz bandwidth, 2.9ms delay.
* 2: 1kHz sampling rate, 92Hz bandwidth, 3.9ms delay.
* 3: 1kHz sampling rate, 41Hz bandwidth, 5.9ms delay.
* 4: 1kHz sampling rate, 20Hz bandwidth, 9.9ms delay.
* 5: 1kHz sampling rate, 10Hz bandwidth, 17.85ms delay.
* 6: 1kHz sampling rate, 5Hz bandwidth, 33.48ms delay.
* @param accel_lpf Accelerometer low pass filter setting, eg: 0
* 7: 1kHz sampling rate, 420Hz 3dB bandwidth, 1.38ms delay.
* 0: 1kHz sampling rate, 218.1Hz 3dB bandwidth, 1.88ms delay.
* 1: 1kHz sampling rate, 218.1Hz 3dB bandwidth, 1.88ms delay.
* 2: 1kHz sampling rate, 99Hz 3dB bandwidth, 2.88ms delay.
* 3: 1kHz sampling rate, 44.8Hz 3dB bandwidth, 4.88ms delay.
* 4: 1kHz sampling rate, 21.2Hz 3dB bandwidth, 8.87ms delay.
* 5: 1kHz sampling rate, 10.2Hz 3dB bandwidth, 16.83ms delay.
* 6: 1kHz sampling rate, 5.05Hz 3dB bandwidth, 32.48ms delay.
*/

bool reset_mpu(int gyro_lpf = 0, int accel_lpf = 0) {
mpu_write(REG_PWR_MGMT_1, 0x80); // H_RESET, internal 20MHz clock
delay(200); // must delay after reset

mpu_write(REG_SIGNAL_PATH_RESET, 0x7); // GYRO_RST | ACCEL_RST | TEMP_RST
mpu_write(REG_USER_CTRL, 0x1); // SIG_COND_RST
mpu_write(REG_CONFIG, gyro_lpf);
mpu_write(REG_GYRO_CONFIG, 0x10); // GYRO_FS_SEL = 3, +-1000 dps, DLPF on
mpu_write(REG_ACCEL_CONFIG, 0x18); // ACCEL_FS_SEL = 3, +-16g, DLPF on
mpu_write(REG_ACCEL_CONFIG2, accel_lpf);
delay(200);
byte x = 255;
if (!mpu_read(REG_GYRO_CONFIG, &x)) {
return false;
}
if (x != 0x10) {
return false;
}
return true;
}

bool compute_biases() {
mpu_write_int16(XG_OFFSET_H, 0);
mpu_write_int16(YG_OFFSET_H, 0);
mpu_write_int16(ZG_OFFSET_H, 0);

const int N = 100;
const int MAX_VAR = 40;
float sum_x = 0, sum_y = 0, sum_z = 0;
float sum_ax = 0, sum_ay = 0, sum_az = 0;
float xs[N];
float ys[N];
float zs[N];
for (int i = 0; i < N; i++) {
short x;
short y;
short z;
if (!mpu_read_int16(REG_GYRO_XOUT_H, &x)) {
return false;
}
if (!mpu_read_int16(REG_GYRO_YOUT_H, &y)) {
return false;
}
if (!mpu_read_int16(REG_GYRO_ZOUT_H, &z)) {
return false;
}
sum_x += x;
sum_y += y;
sum_z += z;
xs[i] = x;
ys[i] = y;
zs[i] = z;
short ax;
short ay;
short az;
if (!mpu_read_int16(REG_ACCEL_XOUT_H, &ax)) {
return false;
}
if (!mpu_read_int16(REG_ACCEL_YOUT_H, &ay)) {
return false;
}
if (!mpu_read_int16(REG_ACCEL_ZOUT_H, &az)) {
return false;
}
sum_ax += ax;
sum_ay += ay;
sum_az += az;
delay(10);
}

float mean_x = sum_x / N;
float mean_y = sum_y / N;
float mean_z = sum_z / N;
float var_x = 0, var_y = 0, var_z = 0;
for (int i = 0; i < N; i++) {
float dx = xs[i] - mean_x;
var_x = var_x + dx * dx;
float dy = ys[i] - mean_y;
var_y = var_y + dy * dy;
float dz = zs[i] - mean_z;
var_z = var_z + dz * dz;
}
var_x = var_x / N;
var_y = var_y / N;
var_z = var_z / N;

float mean_ax = sum_ax / N;
float mean_ay = sum_ay / N;
float mean_az = sum_az / N;

Serial.print("Gyro: mean ");
Serial.print(mean_x);
Serial.print(", ");
Serial.print(mean_y);
Serial.print(", ");
Serial.print(mean_z);
Serial.print(" var ");
Serial.print(var_x);
Serial.print(", ");
Serial.print(var_y);
Serial.print(", ");
Serial.print(var_z);
Serial.print(" Accel: mean ");
Serial.print(mean_ax);
Serial.print(", ");
Serial.print(mean_ay);
Serial.print(", ");
Serial.println(mean_az);
set_gyro_bias(mean_x, mean_y, mean_z);
set_accel_bias(mean_ax, 0, mean_az);
return true;
}

void set_gyro_bias(int x_bias, int y_bias, int z_bias) {
mpu_write_int16(XG_OFFSET_H, -x_bias);
mpu_write_int16(YG_OFFSET_H, -y_bias);
mpu_write_int16(ZG_OFFSET_H, -z_bias);
}

bool set_accel_bias(short x_bias, short y_bias, short z_bias) {
short cur_x;
short cur_y;
short cur_z;
if (!mpu_read_int16(XA_OFFSET_H, &cur_x)) {
return false;
}
if (!mpu_read_int16(YA_OFFSET_H, &cur_y)) {
return false;
}
if (!mpu_read_int16(ZA_OFFSET_H, &cur_z)) {
return false;
}
cur_x -= x_bias;
cur_y -= y_bias;
cur_z -= z_bias;
cur_x &= ~1;
cur_y &= ~1;
cur_z &= ~1;
mpu_write_int16(XA_OFFSET_H, cur_x);
mpu_write_int16(YA_OFFSET_H, cur_y);
mpu_write_int16(ZA_OFFSET_H, cur_z);
return true;
}

//-----------------------------

AF_DCMotor *motor_left;
AF_DCMotor *motor_right;

void motor_move(float v /* -100 to 100 */) {
if (v > 0) {
motor_left->run(BACKWARD);
motor_right->run(FORWARD);
} else {
motor_left->run(FORWARD);
motor_right->run(BACKWARD);
v = -v;
}
if (v > 100) {
v = 100;
}
v = v * 0.7 + 185;
if (v < 195) {
v = 0;
}
motor_left->setSpeed(v);
motor_right->setSpeed(v);
}

void motor_coast() {
motor_left->run(RELEASE);
motor_right->run(RELEASE);
}

//-----------------------------

long last_time = 0;
float motor_out = 0;
int vertical_count = 0;
bool motor_on = false;
float est_angle = 0;
float last_err = 0;
float i_err = 0;


void setup() {
pinMode(LED_BUILTIN, OUTPUT);
for (int i = 0; i < 20; i++) {
digitalWrite(LED_BUILTIN, HIGH);
delay(100);
digitalWrite(LED_BUILTIN, LOW);
delay(100);
}

digitalWrite(SDA, HIGH);
digitalWrite(SCL, HIGH);

Wire.begin();
Wire.setClock(400000);
while (1) {
byte id;
if (mpu_read(WHO_AM_I, &id)) {
if (id == 0x73) {
if (reset_mpu(5, 5)) {
break;
}
}
}
delay(3000);
}
// add 32768/16g = 2048 to the accel axis pointing to ground
//compute_biases();

set_gyro_bias(27, -40, -43);
set_accel_bias(40, 58, 417);

motor_left = new AF_DCMotor(3);
motor_right = new AF_DCMotor(2);
motor_coast();

last_time = millis();
motor_out = 0;
vertical_count = 0;
motor_on = false;
est_angle = 0;
last_err = 0;
i_err = 0;
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
}

bool read_accel_tilt_angle(float *angle) {
short accel_x;
short accel_z;

if (!mpu_read_int16(REG_ACCEL_XOUT_H, &accel_x)) {
return false;
}
if (!mpu_read_int16(REG_ACCEL_ZOUT_H, &accel_z)) {
return false;
}

*angle = atan2(accel_z, -accel_x) * RAD_TO_DEG;
return true;
}

void loop() {
long current_time = millis();
long delta_t = current_time - last_time;
if (delta_t < 5) {
return;
}
short gyro_y;
if (!mpu_read_int16(REG_GYRO_YOUT_H, &gyro_y)) {
return;
}
float accel_angle;
if (!read_accel_tilt_angle(&accel_angle)) {
return;
}
float gyro_angle_rate = float(gyro_y) * -1000.0 / 32768.0; // degrees/s
float gyro_angle_change = gyro_angle_rate * delta_t / 1000; // degrees
est_angle = ((SMOOTHING_FACTOR-1) * (est_angle + gyro_angle_change) + accel_angle) / SMOOTHING_FACTOR;
if (motor_on && (est_angle > 30 || est_angle < -30)) {
last_err = 0;
i_err = 0;
motor_coast();
motor_on = false;
}
float err = est_angle - TARGET_ANGLE;
if (motor_on) {
float d_err = (err - last_err) * 1000 / delta_t;
last_err = err;
i_err = i_err + err * delta_t;
float u = err * KE + d_err * KD + i_err * KI;
motor_out = u;
motor_move(motor_out);
} else if (err <= 5 && err >= -5) {
vertical_count = vertical_count + 1;
if (vertical_count > 100) {
vertical_count = 0;
last_err = 0;
i_err = 0;
motor_on = true;
}
} else if (err <= 5 && err >= -5) {
motor_on = true;
}
last_time = current_time;
}

October 31, 2024

Balancing bot 2024

Recently, I bought a new 3D printer. My 10+ year old printer was long gone. Getting it to print properly was hard, so hard that I stopped using it. Is the new printer any better?


Well, since my balancing bot from 2017 has fallen apart, let's rebuild it!



It has been interesting coming back to this toy after seven years. Surprisingly, all the electronics on the bot still worked. The soldered daughter board remains solid despite all the physical shocks from the bot falling down. An FS90R servo had a broken plastic gear, so that got replaced. The servos are now powered by 4x AA rechargeable batteries. The code is the same except for some tweaks to the PID parameters. The code did not age at all.

Redesigning all the parts took some time. I had certain changes in mind when redesigning the bot. I wanted the new frame to be bigger so that the parts are spread out and accessible. All parts, especially the batteries, must be securely attached.  

Printing was the easiest part. The printer just works out of the box. I could concentrate on designing instead of tinkering with the printer to get it to work. It is a reliable workhorse, just as it should be.

So, I have been making stuff, including yet another balancing bot:


November 01, 2020

Balancing Bot Update 2020


Since the last post three years ago, Micro:bit MakeCode has been updated.

The latest version is MakeCode v3 2020 Update. The balancing bot code was written using MakeCode v0. MakeCode v3 is not compatible with MakeCode v0.

The big incompatible change is that numbers in MakeCode v3 are now floating point while numbers in MakeCode v0 were 16 bit integers. MakeCode v3 also includes trigonometric functions in its library.

Here's the updated bot code that works with MakeCode v3. The Trig library should be removed from the custom.ts file. It is not needed anymore.

/**
 * Public domain. Use at your own risk!
 */
let TARGET_ANGLE = 155
let KE = 420
let KD = 8
let KI = 5
let motor_left_bias = -2;
let motor_right_bias = 2;
function control_loop() {
    motor_coast()
    let motor_out = 0;
    let vertical_count = 0;
    let motor_on = false
    let est_angle = read_accel_tilt_angle()
    let start_time = input.runningTime()
    let last_time = start_time
    let last_err = 0;
    let i_err = 0;
    while (true) {
        let current_time = input.runningTime()
        let delta_t = current_time - last_time
        last_time = current_time
        est_angle = updateAngle(est_angle, delta_t)
        if (motor_on && (est_angle > 3000 || est_angle < -3000)) {
            motor_coast()
            motor_on = false
        }
        let err = est_angle - TARGET_ANGLE
        if (motor_on) {
            let d_err = (err - last_err) * 1000 / delta_t
            last_err = err
            i_err = i_err + err * delta_t
            let u = err * KE + d_err * KD + i_err * KI
            motor_out = Math.clamp(-90, 90, u / 10000)
            motor_move(motor_out + motor_left_bias, motor_out + motor_right_bias)
        } else if (err <= 500 && err >= -500) {
            vertical_count = vertical_count + 1
            if (vertical_count > 100) {
                vertical_count = 0
                last_err = 0
                i_err = 0
                est_angle = read_accel_tilt_angle()
                motor_on = true
            }   
        } else {
            vertical_count = 0
        }        
        basic.pause(1)
    }
}

function read_gyro_angle_rate(): number {
    InvMPU.read_gyro()
    return -InvMPU.gyro_y
}

function read_accel_tilt_angle(): number {
    InvMPU.read_accel()
    return Math.round(Math.atan2(InvMPU.accel_z, -InvMPU.accel_x) * 18000 / Math.PI)
}

function updateAngle(old_angle: number, delta_t_ms: number): number {
    let accel_angle = read_accel_tilt_angle()
    let gyro_angle_rate = read_gyro_angle_rate() * 200000 / 32768
    let gyro_angle_change = gyro_angle_rate * delta_t_ms / 1000
    return (49 * (old_angle + gyro_angle_change) + accel_angle) / 50
}

function motor_coast() {
    pins.digitalWritePin(DigitalPin.P15, 0)
    pins.digitalWritePin(DigitalPin.P16, 0)
}

function motor_move(left: number, right: number) {
    pins.servoWritePin(AnalogPin.P15, 90 - right)
    pins.servoWritePin(AnalogPin.P16, 90 + left)
}

input.onButtonPressed(Button.A, function on_button_pressed_a() {
    TARGET_ANGLE = TARGET_ANGLE + 5
})

input.onButtonPressed(Button.B, function on_button_pressed_b() {
    TARGET_ANGLE = TARGET_ANGLE - 5
})

input.onButtonPressed(Button.AB, function on_button_pressed_ab() {
    basic.showNumber(TARGET_ANGLE)
})

if (InvMPU.find_mpu()) {
    basic.showIcon(IconNames.Happy)
    InvMPU.reset_mpu(5, 5)
    basic.pause(100)
    InvMPU.set_gyro_bias(5, 1, -13)
    control_loop()
} else {
    basic.showIcon(IconNames.No)
}

November 18, 2017

Self-balancing robot version 3 update!


It works! Now it balances on hard or soft floors for more than 30 minutes!



What changed?

Firstly, 2xAA rechargeable Eneloop batteries are insufficient to power those FS90R motors. The specification of the motor allows up to 6V. Two cells provide only around 2.7V total. I switch to 4xAA Eneloop batteries, providing around 5.4V. The motors were much much faster, more than twice as fast. The immediate consequence of this is that the PID parameters need to be re-tuned and scaled down to 10-20% of the values for 2xAA batteries.

Secondly, I turned up the builtin digital low pass filter in the MPU-9250 aggressively. Now it is set to 5 for both accelerometer and gyroscope. That translates to a sensor delay of 17ms and the 3dB bandwidth of about 10Hz. That is probably averaging around 17 samples at 1kHz sample rate. And that did the trick!

Here's a graph of motor power, gyroscope angular velocity and tilt angle.


The filtered angular velocity seldom exceeds 0.3 degrees per second. The filtered tilt angle seldom exceeds 1 degree. The motor power is mostly less than 10% of maximum power.

I've updated the InvenSense MPU-9255/MPU-9250/MPU-6500 module. You can now specify the low pass filter level for the accelerometer and gyroscope in the call to InvMPU.reset_mpu(). Copy this new version into your custom.ts.

The only changes from the version 1 code are the PID tuning parameters and the call InvMPU.reset_mpu(5, 5).

See the previous post on the parts for building version 3.



November 16, 2017

Self-balancing robot version 3


Version 1 was made out of Lego. It keeps breaking into pieces, the motors were not secured and it also contained the unnecessary Kitronic servo:lite board. So, I rebuilt it.

Parts:

The code for this version is identical to the code for version 1 except the tweek for a different orientation of the MPU-9255. With 2x AA batteries, identical PID parameters will work. With 4x AA batteries, the parameters have to be retuned.

But, alas, it still doesn't balance well on smooth hard floors!

It works fine on carpet or cushion even though it is only half the height of the version 1 robot. It just won't work on wood or marble floors!

After much tuning, I decided to record the motor response. I added two more wheels and turned the bot into a "car". Then I recorded the horizontal acceleration using the accelerometer in response to various motor control like a 1 second 66% power pulse. Here is a typical result with 2x AA batteries:


Why is the acceleration oscillating around zero? The amplitudes of the oscillations are much worse with 4x AA batteries.

Oh, the motor controller in the servo is a closed loop controller!

The closed-loop controller inside the FS90R is probably a variant of the standard PID controller. The oscillations are caused by the controller trying to match the output voltage to the pulse duration.

The accelerometer and gyroscope are picking up physical feedback from the controller's actions. On soft floor like carpet, the feedback is dampened physically. On hard floors, the sensors pick up random spikes that throws the PID algorithm off.

On top of that, the accelerometer only picks up the increase in motor speed after about 60ms!

In short, don't build a self-balancing robot using servo motors. Just use DC motors.

Update: I've fixed the problem and got it to work on hard floors too!


November 08, 2017

Code for self-balancing micro:bit robot with DC motors



The DC motors version of the code is similar to the servo version except for the motor control code and the tuning parameters.

This works with version 2 of the self-balancing robot.

See the code for version 1 for more info.


/**
 * Public domain. Use at your own risk!
 * Self-balancing robot controller, controlling a pair of FS90R servos.
 * Requires InvMPU and Trig package in custom.ts.
 * Update read_gyro_angle_rate() and read_accel_tilt_angle() to sensor mounting.
 * Update call to InvMPU.set_gyro_bias() with the bias of your sensor.
 */

// Tuning Parameters
const TARGET_ANGLE = -560; // forward tilt from vertical in degrees * 100
const KE = 2400;
const KD = 24;
const KI = 30;

const motor_bias = 0; // increase to reduce forward power to the right

function read_gyro_angle_rate(): number {
    InvMPU.read_gyro()
    return -InvMPU.gyro_y
}

function read_accel_tilt_angle(): number {
    InvMPU.read_accel()
    return Trig.atan2(-InvMPU.accel_z, InvMPU.accel_x); // degrees * 100
}

function updateAngle(est_angle: number, delta_t_ms: number): number {
    let accel_angle = read_accel_tilt_angle(); // degrees * 100
    let gyro_angle_rate = read_gyro_angle_rate() * 200000 / 32768; // (degrees * 100) per second
    let gyro_angle_change = gyro_angle_rate * delta_t_ms / 1000; // degrees * 100
    let new_est_angle = (49 * (est_angle + gyro_angle_change) + accel_angle) / 50;
    return new_est_angle;
}

// Left motor connected with L293D
const motor_a_enable = AnalogPin.P13; // enable 1-2
const motor_a1 = DigitalPin.P2; // input 1
const motor_a2 = DigitalPin.P12; // input 2

// Right motor connect with L293D
const motor_b_enable = AnalogPin.P14; // enable 3-4
const motor_b1 = DigitalPin.P15; // input 3
const motor_b2 = DigitalPin.P16; // input 4

function motor_coast() {
    pins.analogWritePin(motor_a_enable, 0);
    pins.digitalWritePin(motor_a1, 0);
    pins.digitalWritePin(motor_a2, 0);
    pins.analogWritePin(motor_b_enable, 0);
    pins.digitalWritePin(motor_b1, 0);
    pins.digitalWritePin(motor_b2, 0);
}

function motor_move(left: number, right: number) {
    if (left >= 0) {
        pins.analogWritePin(motor_a_enable, left);
        pins.digitalWritePin(motor_a1, 1);
        pins.digitalWritePin(motor_a2, 0);
    } else {
        pins.analogWritePin(motor_a_enable, -left);
        pins.digitalWritePin(motor_a1, 0);
        pins.digitalWritePin(motor_a2, 1);
    }
    if (right >= 0) {
        pins.analogWritePin(motor_b_enable, right);
        pins.digitalWritePin(motor_b1, 1);
        pins.digitalWritePin(motor_b2, 0);
    } else {
        pins.analogWritePin(motor_b_enable, -right);
        pins.digitalWritePin(motor_b1, 0);
        pins.digitalWritePin(motor_b2, 1);
    }
}

function setup() {
    basic.showIcon(IconNames.Happy);
    while (true) {
        while (!input.buttonIsPressed(Button.A)) {
            basic.pause(10);
        }
        if (InvMPU.find_mpu()) {
            break;
        }
        basic.showIcon(IconNames.No);
    }
    InvMPU.reset_mpu();
    basic.pause(100);
    basic.clearScreen();
    InvMPU.set_gyro_bias(5, 1, -13); // set this for your sensor
}

function control_loop() {
    let motor_on = false;
    let est_angle = read_accel_tilt_angle(); // degrees * 100 from vertical
    let last_err = 0;
    let i_err = 0;
    let last_time = input.runningTime();
    while (true) {
        let current_time = input.runningTime();
        let delta_t = current_time - last_time;
        last_time = current_time;
        est_angle = updateAngle(est_angle, delta_t);
        if (motor_on && (est_angle > 3000 || est_angle < -3000)) {
            last_err = 0;
            i_err = 0;
            motor_coast();
            motor_on = false;
        }
        let err = est_angle - TARGET_ANGLE;
        if (motor_on) {
            let d_err = (err - last_err) * 1000 / delta_t;
            last_err = err;
            i_err = i_err + err * delta_t;
            let u = err * KE + d_err * KD + i_err * KI;
            let motor_out = u / 1000;
            let motor_right = motor_out - motor_bias;
            let motor_left = motor_out + motor_bias;
            motor_move(Math.clamp(-1024, 1023, motor_left), Math.clamp(-1024, 1023, motor_right));
        } else if (err <= 500 && err >= -500) {
            motor_on = true;
        }
        basic.pause(5);
    }
}

setup();
control_loop();

November 07, 2017

Code for self-balancing micro:bit robot with FS90R servo motors



Ok, here's the code for version 1 of the self-balancing robot. I tried to make this work in block mode in MakeCode. The result was unreadable.

Only 80 lines of code. It implements the most primitive PID control algorithm. Clearly Segway and other self-balancing single wheel devices use far better algorithms.

To use this, you neeed to:

  • Build a robot with one of three InvenSense motion sensors and FS90R or other servo motors.
  • Add the InvMPU and Trig packages from the last post to custom.ts.
  • Copy and paste this code in main.ts.
  • Set the gyro bias using the values computed in the sample program from the last post.
  • Change read_gyro_angle_rate() and read_accel_tilt_angle() based on how the sensor is mounted on the robot.
  • Tune TARGET_ANGLE, KE, KD and KI.

When the happy face appears, press the A button to locate the sensor and start the bot. When the bot is near vertical, it will turn on the motors to balance. If the angle is too far off vertical, it will shut down the motors. Hold it vertical to start balancing again.

Here it is:


/**
 * Public domain. Use at your own risk!
 * Self-balancing robot controller, controlling a pair of FS90R servos.
 * Requires InvMPU and Trig package in custom.ts.
 * Update read_gyro_angle_rate() and read_accel_tilt_angle() to sensor mounting.
 * Update call to InvMPU.set_gyro_bias() with the bias of your sensor.
 */

// Tuning Parameters
const TARGET_ANGLE = 50; // forward tilt from vertical in degrees * 100
const KE = 1200;
const KD = 24;
const KI = 24;

const motor_bias = 0; // increase to reduce forward power to the right

function read_gyro_angle_rate(): number {
    InvMPU.read_gyro()
    return -InvMPU.gyro_y
}

function read_accel_tilt_angle(): number {
    InvMPU.read_accel()
    return Trig.atan2(InvMPU.accel_z, -InvMPU.accel_x); // degrees * 100
}

function updateAngle(est_angle: number, delta_t_ms: number): number {
    let accel_angle = read_accel_tilt_angle(); // degrees * 100
    let gyro_angle_rate = read_gyro_angle_rate() * 200000 / 32768; // (degrees * 100) per second
    let gyro_angle_change = gyro_angle_rate * delta_t_ms / 1000; // degrees * 100
    let new_est_angle = (49 * (est_angle + gyro_angle_change) + accel_angle) / 50;
    return new_est_angle;
}

function setup() {
    basic.showIcon(IconNames.Happy);
    while (true) {
        while (!input.buttonIsPressed(Button.A)) {
            basic.pause(10);
        }
        if (InvMPU.find_mpu()) {
            break;
        }
        basic.showIcon(IconNames.No);
    }
    InvMPU.reset_mpu();
    basic.pause(100);
    basic.clearScreen();
    InvMPU.set_gyro_bias(5, 1, -13); // set this for your sensor
}

function control_loop() {
    let motor_on = false;
    let est_angle = read_accel_tilt_angle(); // degrees * 100 from vertical
    let last_err = 0;
    let i_err = 0;
    let last_time = input.runningTime();
    while (true) {
        let current_time = input.runningTime();
        let delta_t = current_time - last_time;
        last_time = current_time;
        est_angle = updateAngle(est_angle, delta_t);
        if (motor_on && (est_angle > 3000 || est_angle < -3000)) {
            last_err = 0;
            i_err = 0;
            pins.digitalWritePin(DigitalPin.P15, 0);
            pins.digitalWritePin(DigitalPin.P16, 0);
            motor_on = false;
        }
        let err = est_angle - TARGET_ANGLE;
        if (motor_on) {
            let d_err = (err - last_err) * 1000 / delta_t;
            last_err = err;
            i_err = i_err + err * delta_t;
            let u = err * KE + d_err * KD + i_err * KI;
            let motor_out = u / 10000;
            pins.servoWritePin(AnalogPin.P15, 90 - Math.clamp(-90, 90, motor_out - motor_bias)); // R
            pins.servoWritePin(AnalogPin.P16, 90 + Math.clamp(-90, 90, motor_out + motor_bias)); // L
        } else if (err <= 500 && err >= -500) {
            motor_on = true;
        }
        basic.pause(5);
    }
}

setup();
control_loop();


See the next post for a version of this code that works with DC motors.

InvenSense MPU-9255/MPU-9250/MPU-6500 gyroscope accelerometer and compass




EDIT: Arduino version of here.

The BBC micro:bit does not have a builtin gyroscope and the self-balancing robot requires one.

Among the many options, the MPU-6500/MPU-9250/MPU-9255 based breakout boards are probably among the cheapest motion sensors available. The MPU-6500 costs SGD9.90 from a local retail shop and is available online for much less. The differences between the models are:

  • MPU-6500: gyroscope and accelerometer, 6 axis.
  • MPU-9250: gyroscope, accelerometer and compass, 9 axis
  • MPU-9255: same as MPU-9250 (almost)

The gyroscope and accelerometer are identical across all three models. Each axis has 16 bits of resolution. The gyroscope measures up to +- 2000 degrees per second. The accelerometer measures up to +-16g. The builtin accelerometer on the micro:bit only has 11 bits of resolution and a range of +-4g.

There are no drivers or library for these chips for the micro:bit. InvenSense provides product specification and register map documents, enough to figure out how to interface with the chips. I can ignore the  advanced features like the FIFO buffer, interrupts and the digital motion processor. I just need to configure the chips, read the gyroscope and accelerometer values.

So, if you need a cheap gyroscope and accelerometer that works with micro:bit, here's a working library you can add to your code.

Hardware instructions
  • Connect VCC and GND to the 3V and GND pins on the micro:bit respectively.
  • Connect SCL and SDA to pin 19 and 20 on the micro:bit respectively. These are the default I2C pins.
  • Connect AD0 to GND to select the default I2C address.

Software instructions
  • Create a new project on MakeCode.
  • Click on the arrow at the bottom left to show the simulator.
  • Click "{} Javascript" to switch to Javascript mode.
  • Click on "Explorer" to expand the Explorer tree.
  • Click on the "+" on the Explorer bar to add a custom.ts script.
  • Click "Go ahead!" on the "Add custom blocks?" prompt.
  • Now, it should be showing the custom.ts script. Delete all the default code.
If your project already has a custom.ts script, ignore the above instructions. Just switch to that script.

Now copy and append the code below to the end of your custom.ts.

Update: reset_mpu() now takes two parameters gyro_lpf and accel_lpf to control the digital low pass filter.

/**
 * Public domain. Use at your own risk!
 * Simplified interface for InvenSense MPU-6500, MPU-9250, MPU-9255
 */
//% weight=90 color=#0040A0
namespace InvMPU {
    export const MPU_6500_ID = 0x70;
    export const MPU_9250_ID = 0x71;
    export const MPU_9255_ID = 0x73;

    const MPU_ADDR = 0x68;
    const WHO_AM_I = 0x75;
    const REG_PWR_MGMT_1 = 0x6b;
    const REG_SIGNAL_PATH_RESET = 0x68;
    const REG_USER_CTRL = 0x6a;
    const REG_ACCEL_XOUT_H = 0x3b;
    const REG_ACCEL_YOUT_H = 0x3d;
    const REG_ACCEL_ZOUT_H = 0x3f;
    const REG_GYRO_XOUT_H = 0x43;
    const REG_GYRO_YOUT_H = 0x45;
    const REG_GYRO_ZOUT_H = 0x47;
    const REG_CONFIG = 0x1a;
    const REG_GYRO_CONFIG = 0x1b;
    const REG_ACCEL_CONFIG = 0x1c;
    const REG_ACCEL_CONFIG2 = 0x1d;
    const XG_OFFSET_H = 0x13;
    const YG_OFFSET_H = 0x15;
    const ZG_OFFSET_H = 0x17;

    function mpu_read(reg: number): number {
        pins.i2cWriteNumber(MPU_ADDR, reg, NumberFormat.UInt8BE, true);
        return pins.i2cReadNumber(MPU_ADDR, NumberFormat.UInt8BE, false);
    }

    function mpu_read_int16(reg: number): number {
        pins.i2cWriteNumber(MPU_ADDR, reg, NumberFormat.UInt8BE, true);
        return pins.i2cReadNumber(MPU_ADDR, NumberFormat.Int16BE, false);
    }

    function mpu_write(reg: number, data: number) {
        pins.i2cWriteNumber(MPU_ADDR, reg << 8 | (data & 0xff), NumberFormat.UInt16BE);
    }

    function mpu_write_int16(reg: number, data: number) {
        mpu_write(reg, (data >> 8) & 0xff);
        mpu_write(reg + 1, data & 0xff);
    }

    /**
     * Contains one of MPU_6500_ID, MPU_9250_ID, MPU_9255_ID or zero.
     */
    //% block
    export let sensor_id = 0;

    /**
     * Look for a MPU-6500, MPU-9250 or MPU-9255.
     * Returns true if the MPU was found.
     * The MPU id is in sensor_id.
     */
    //% block
    //% weight=99
    export function find_mpu(): boolean {
        sensor_id = mpu_read(WHO_AM_I);
        return sensor_id == MPU_9255_ID || sensor_id == MPU_9250_ID || sensor_id == MPU_6500_ID;
    }

    /**
     * Reset the MPU and configure the gyroscope to +- 2000 degrees/second and the accelerometer to +-16g.
     * The low pass filter settings control how sensitive the sensors are to quick changes.
     * In order of increasing sensitivity: 6, 5, 4, 3, 2, 1, 0, 7
     * Info from MPU-9250 register map document.
     * @param gyro_lpf Gyroscope low pass filter setting, eg: 0
     *   7: 8kHz sampling rate, 36001Hz bandwidth, 0.17ms delay.
     *   0: 8kHz sampling rate, 250Hz bandwidth, 0.97ms delay.
     *   1: 1kHz sampling rate, 184Hz bandwidth, 2.9ms delay.
     *   2: 1kHz sampling rate, 92Hz bandwidth, 3.9ms delay.
     *   3: 1kHz sampling rate, 41Hz bandwidth, 5.9ms delay.
     *   4: 1kHz sampling rate, 20Hz bandwidth, 9.9ms delay.
     *   5: 1kHz sampling rate, 10Hz bandwidth, 17.85ms delay.
     *   6: 1kHz sampling rate, 5Hz bandwidth, 33.48ms delay.
     * @param accel_lpf Accelerometer low pass filter setting, eg: 0
     *   7: 1kHz sampling rate, 420Hz 3dB bandwidth, 1.38ms delay.
     *   0: 1kHz sampling rate, 218.1Hz 3dB bandwidth, 1.88ms delay.
     *   1: 1kHz sampling rate, 218.1Hz 3dB bandwidth, 1.88ms delay.
     *   2: 1kHz sampling rate, 99Hz 3dB bandwidth, 2.88ms delay.
     *   3: 1kHz sampling rate, 44.8Hz 3dB bandwidth, 4.88ms delay.
     *   4: 1kHz sampling rate, 21.2Hz 3dB bandwidth, 8.87ms delay.
     *   5: 1kHz sampling rate, 10.2Hz 3dB bandwidth, 16.83ms delay.
     *   6: 1kHz sampling rate, 5.05Hz 3dB bandwidth, 32.48ms delay.
     */
    //% block
    //% weight=98
    export function reset_mpu(gyro_lpf=0, accel_lpf=0) {
        control.assert(gyro_lpf >= 0 || gyro_lpf <= 7, "gyro_lpf must be between 0 and 7");
        control.assert(accel_lpf >= 0 || accel_lpf <= 7, "accel_lpf must be between 0 and 7");
        mpu_write(REG_PWR_MGMT_1, 0x80); // H_RESET, internal 20MHz clock
        mpu_write(REG_SIGNAL_PATH_RESET, 0x7); // GYRO_RST | ACCEL_RST | TEMP_RST
        mpu_write(REG_USER_CTRL, 0x1); // SIG_COND_RST
        mpu_write(REG_CONFIG, gyro_lpf); 
        mpu_write(REG_GYRO_CONFIG, 0x18); // GYRO_FS_SEL = 3, +-2000 dps, DLPF on
        mpu_write(REG_ACCEL_CONFIG, 0x18); // ACCEL_FS_SEL = 3, +-16g
        mpu_write(REG_ACCEL_CONFIG2, accel_lpf); // DLPF on
    }

    /**
     * Gyro X axis value after calling read_gyro().
     * Value from -32768 to 32767.
     */
    //% block
    export let gyro_x = 0;

    /**
     * Gyro Y axis value after calling read_gyro().
     * Value from -32768 to 32767.
     */
    //% block
    export let gyro_y = 0;

    /**
     * Gyro Z axis value after calling read_gyro().
     * Value from -32768 to 32767.
     */
    //% block
    export let gyro_z = 0;

    /**
     * Read all three gyroscope axis values and store them in gyro_x, gyro_y and gyro_z.
     */
    //% block
    //% weight=95
    export function read_gyro() {
        gyro_x = mpu_read_int16(REG_GYRO_XOUT_H);
        gyro_y = mpu_read_int16(REG_GYRO_YOUT_H);
        gyro_z = mpu_read_int16(REG_GYRO_ZOUT_H);
    }

    /**
     * Accelerometer X axis value after calling read_accel().
     * Value from -32768 to 32767.
     */
    //% block
    export let accel_x = 0;

    /**
     * Accelerometer Y axis value after calling read_accel().
     * Value from -32768 to 32767.
     */
    //% block
    export let accel_y = 0;

    /**
     * Accelerometer Z axis value after calling read_accel().
     * Value from -32768 to 32767.
     */
    //% block
    export let accel_z = 0;

    /**
     * Read all three accelerometer values and store them in accel_x, accel_y and accel_z.
     */
    //% block
    //% weight=94
    export function read_accel() {
        accel_x = mpu_read_int16(REG_ACCEL_XOUT_H);
        accel_y = mpu_read_int16(REG_ACCEL_YOUT_H);
        accel_z = mpu_read_int16(REG_ACCEL_ZOUT_H);
    }

    export let var_x = 0;
    export let var_y = 0;
    export let var_z = 0;

    /**
     * Gyro X axis bias after calling get_gyro_bias().
     */
    //% block
    export let gyro_x_bias = 0;

    /**
     * Gyro Y axis bias after calling get_gyro_bias().
     */
    //% block
    export let gyro_y_bias = 0;

    /**
     * Gyro Z axis bias after calling get_gyro_bias().
     */
    //% block
    export let gyro_z_bias = 0;

    /**
     * Compute the gyro bias for all three axis. The bias for each axis is the average of 100 samples.
     * Returns true if the sensor is steady enough to calculate the bias.
     * The bias values are store in gyro_x_bias, gyro_y_bias and gyro_z_bias.
     */
    //% block
    //% weight=97
    export function compute_gyro_bias(): boolean {
        mpu_write_int16(XG_OFFSET_H, 0);
        mpu_write_int16(YG_OFFSET_H, 0);
        mpu_write_int16(ZG_OFFSET_H, 0);
        const N = 100;
        const MAX_VAR = 40;
        let sum_x = 0, sum_y = 0, sum_z = 0;
        let xs: number[] = [], ys: number[] = [], zs: number[] = [];
        for (let i = 0; i < N; i++) {
            let x = mpu_read_int16(REG_GYRO_XOUT_H);
            let y = mpu_read_int16(REG_GYRO_YOUT_H);
            let z = mpu_read_int16(REG_GYRO_ZOUT_H);
            sum_x += x;
            sum_y += y;
            sum_z += z;
            xs.push(x);
            ys.push(y);
            zs.push(z);
            basic.pause(1);
        }
        let mean_x = sum_x / N;
        let mean_y = sum_y / N;
        let mean_z = sum_z / N;
        var_x = 0;
        var_y = 0;
        var_z = 0;
        for (let i = 0; i < N; i++) {
            let dx = xs[i] - mean_x;
            var_x = var_x + dx * dx;
            let dy = ys[i] - mean_y;
            var_y = var_y + dy * dy;
            let dz = zs[i] - mean_z;
            var_z = var_z + dz * dz;
        }
        var_x = var_x / N;
        var_y = var_y / N;
        var_z = var_z / N;
        if (var_x > MAX_VAR || var_y > MAX_VAR || var_z > MAX_VAR) {
            return false;
        }
        gyro_x_bias = mean_x;
        gyro_y_bias = mean_y;
        gyro_z_bias = mean_z;
        return true;
    }

    /**
     * Set the gyro bias. The bias can be calculated by calling get_gyro_bias().
     * @param x_bias Bias in the X direction, eg: 0
     * @param y_bias Bias in the Y direction, eg: 0
     * @param z_bias Bias in the Z direction, eg: 0
     */
    //% block
    //% weight=96
    export function set_gyro_bias(x_bias: number, y_bias: number, z_bias: number) {
        mpu_write_int16(XG_OFFSET_H, -2 * x_bias);
        mpu_write_int16(YG_OFFSET_H, -2 * y_bias);
        mpu_write_int16(ZG_OFFSET_H, -2 * z_bias);
    }
}

Switch back to main.ts and reload your project. Your main code can now access blocks and javascript that talks to the motion sensor chips.

The InvMPU package contains these functions and they are also available as blocks from the blocks interface of MakeCode:

  • find_mpu(): find one of the three MPUs on the I2C bus and returns true if found.
  • reset_mpu(): reset the MPU and configure it to +-16g and 2000 degrees per second.
  • compute_gyro_bias(): compute the gyroscope bias. The sensor must be stationary.
  • set_gyro_bias(): set the gyroscope bias to values computed in previous calls in get_gyro_bias().
  • read_gyro(): read all three gyroscope axis values.
  • read_accel(): read all three accelerometer values.

One more thing, we really want to know the angle the sensor or robot is tilted from vertical. The axis parallel to the wheels is fixed. We can calculate the angle from the other two axes of the accelerometer using the inverse tangent function atan2(). Unfortunately, the micro:bit does not provide this function or support floating point numbers.

No worries. Here my little approximation of atan2() that takes two signed 16 bits values from the accelerometer and returns 100 times the angle in degrees. For example, if Trig.atan2() returns 2050, it means the angle is 20.5 degrees.

Copy and append the Trig module for micro:bit to the end of your custom.ts.

Update Jan 2021: MakeCode v3 now supports trigonometry functions. Instead of Trig.atan2, use Math.atan2(), convert to degrees and round the result to an integer.

Here's sample code that finds the mpu, resets it, computes the gyro bias, sets the gyro bias and prints values from the gyroscope and accelerometer and the tilt angle on the serial line.

BTW, the bias values are reasonably stable for each hardware breakout board. I use the bias values calculated by the sample program in the balancing code so that I don't have to recompute the bias each time I turn the robot on.

let angle = 0
basic.showIcon(IconNames.Happy)
while (true) {
    while (!(input.buttonIsPressed(Button.A))) {
        basic.pause(100)
    }
    basic.showIcon(IconNames.Diamond)
    if (!(InvMPU.find_mpu())) {
        if (InvMPU.sensor_id != 0) {
            serial.writeLine("Unknown sensor id " + InvMPU.sensor_id)
        }
        serial.writeLine("Cannot find MPU-6500, MPU-6500 or MPU-9255")
        basic.showIcon(IconNames.No)
    } else {
        if (InvMPU.sensor_id == InvMPU.MPU_6500_ID) {
            serial.writeLine("MPU-6500")
        }
        if (InvMPU.sensor_id == InvMPU.MPU_9250_ID) {
            serial.writeLine("MPU-9250")
        }
        if (InvMPU.sensor_id == InvMPU.MPU_9255_ID) {
            serial.writeLine("MPU-9255")
        }
        InvMPU.reset_mpu()
        basic.pause(2000)
        basic.clearScreen()
        if (InvMPU.compute_gyro_bias()) {
            serial.writeLine("X variance " + InvMPU.var_x)
            serial.writeLine("Y variance " + InvMPU.var_y)
            serial.writeLine("Z variance " + InvMPU.var_z)
            serial.writeLine("X bias " + InvMPU.gyro_x_bias)
            serial.writeLine("Y bias " + InvMPU.gyro_y_bias)
            serial.writeLine("Z bias " + InvMPU.gyro_z_bias)
            InvMPU.set_gyro_bias(InvMPU.gyro_x_bias, InvMPU.gyro_y_bias, InvMPU.gyro_z_bias)
            break;
        } else {
            basic.showIcon(IconNames.Angry)
        }
    }
}
basic.showIcon(IconNames.Yes)
while (true) {
    InvMPU.read_gyro()
    InvMPU.read_accel()
    angle = Trig.atan2(InvMPU.accel_z, 0 - InvMPU.accel_x)
    serial.writeLine("Gyro: " + InvMPU.gyro_x + " " + InvMPU.gyro_y + " " + InvMPU.gyro_z + " Angle: " + angle + " Accel: " + InvMPU.accel_x + " " + InvMPU.accel_y + " " + InvMPU.accel_z)
    basic.pause(100)
}


Coming up, code for the self-balancing robot.

Public domain. 

Use at your own risk!