View on GitHub

Welcome to the MABEL docs!

MABEL is a feature-packed, open-source, legged balancing robot based off of the Boston Dynamics Handle robot.

MABEL (Multi Axis Balancer Electronically Levelled)

MABEL

Table of contents

About MABEL

MABEL is an ongoing open source self balancing robot project that is inspired by the famous Boston Dynamics Handle robot. The robot is controlled via an Arduino that handles all of the PID calculations (based off of open source YABR firmware) based on the angle received from an MPU-6050 Accelerometer/Gyro, whilst a Raspberry pi (code in python) manages Bluetooth and servo control, running an inverse kinematics algorithm to translate the robot legs perfectly in two axes.

The goal of MABEL is to create an affordable legged balancing robot platform like the the Boston Dynamics Handle robot that can built on a hobby scale using cheap Amazon parts and components.

By having a balancing platform with articulated legs MABEL will be able to actively balance in multiple Axes and vary leg length depending on the surroundings to increase terrain and off-road performance.

MABEL has built on the open source YABR project for the PID controller but with the addition of servos and a pi that helps interface them and control everything.

Features and design

Some of the stand-out features that make MABEL different from other balancing robots are:

Bill of materials

3D Printable

3D Printable files are found in /CAD/3D Models (To Print)

Non 3D Printable

Here are the Non 3D printable materials to build MABEL that must be either purchased or sourced. This includes all of the electronics, mechanical hardware and fixings. It is recommended to overbuy the nuts and bolts fixings, as the exact number can change between builds. This amazon list contains a rough idea of what needs to be purchased.

Electronic components

Mechanical components

Build instructions

UNDER CONSTRUCTION: This section will include:

Mechanical assembly


Step 1: Press the bearings into the joints

push fit the bearings and secure with a nut and bolt

Each leg section (UpperLeg and LowerLeg) requires two bearings (thats 8x bearings in total) to push fit on opposing sides to ensure smooth rotation. The bearings can be quite tricky to fit so it’s advisable to either apply slow, even pressure with a bench vice, or to soften the plastic with a hairdryer to make it easier to push in by hand. Once you’ve fitted the bearings, you need to push an M5 (4x in total) (30mm) bolt through the hole left and secure with a locknut. More reference images for Step 1


Step 2: Attach 4x Servos to the UpperLeg(s)and BodyPanel(s) using M4 (15mm) bolts

Attach servos with M4 bolt

4x MG996R servos must be secured to 2x BodyPanel and 2x UpperLeg using 4x M4 (15mm) bolts (16x in total). The servos must sit flat against these parts with the shaft facing towards the outside of the robot. Your servos may have a small rib that you can easily sand or file off to get the servo to sit in this orientation. More reference images for Step 2


Step 3: Push fit and screw the servo horns into the DriverGear(s) and attach the assemblies to the servos

push fit servo horns and attach gear to servo

Take your 4x DriverGear parts and 4x Aluminium Servo horns and push it into the recess on the bottom of the gear. Then secure the servo horns to each of the gears using the screws that (should) come with servo horns. Once the gear assembly has been completed, screw it on to the servo shaft using one M3 (10mm) bolt per servo. More reference images for Step 3


Step 4: Attach the NEMA17 Motors to the LowerLeg and fit the wheels

push fit wheels, attach motors

Secure one NEMA17 (2x in total) stepper motor to each of your (2x) LowerLeg parts with 4x M3 (10mm) bolts (8x in total). Next, prepare your wheels and then push fit onto the NEMA17 shafts, securing if necessary with an M4 bolt:

More reference images for Step 4


Step 5: Attach the LowerLeg, UpperLeg and BodyPanel assemblies together using 4x M5 locknuts

Attach all assemblies so far together

Now that you have fitted the BodyPanel and UpperLeg parts with servos (Step 2) and gears (Step 3), and prepared the UpperLeg and LowerLeg sections with bearings, an M5 bolt and a lock nut each (Step 1), you can insert the UpperLeg section into the BodyPanel and secure it with a locknut on the back (servo) side. Then, secure the LowerLeg assembly to the UpperLeg assembly with another M5 locknut to form one leg. This step should then be repeated for the side.

NOTE: When fitting the parts together, special attention should be considered to the position of the servo rotors. With standard 180 degree servos, full range of motion is only possible with one way of the legs being bent (The minimum leg height requires a greater than 90 degree angle for example) - decide which way the legs should bend out and turn the servo gear manually by hand to allow a greater range of motion in that direction than the other (it will be opposite because of the gear drive). You will then calibrate the servos later on with a new 0 position that’s needed for the legs to work properly.

More reference images for Step 5


Electronics Assembly

This section will contain instructions about the construction of the robot electronics


Installation

Required Libraries/Dependencies

The MABEL project relies on multiple open-source and independent libraries, whilst MABELs own classses and functions may run natively, certain libraries are required for full functionality.

The controller code is still under development, however the approxeng.input library is recommended to develop controller code with - Versions for both the approxeng.input libary and Cwiid will be released eventually.

Aftere following the installation instructions for the ServoKit and controller library of your choice, you should be able to clone to the Raspberry Pi with git clone https://www.github.com/raspibotics/MABEL, all controller code, and other scripts should be written in the MABEL/raspi_code/ directory so that the code will be able to reference the code already included.

Usage

IKSolve - (Inverse Kinematics for MABEL)

IKSolve is the class that handles the inverse kinematics functionality for MABEL (IKSolve.py) and allows for the legs to be translated using (x, y) coordinates. It’s really simple to use, all that you need to specify are the home values of each servo (these are the angles that when passed over to your servos, make the legs point directly and straight downwards at 90 degrees). Keep in mind that the values below are just my servo home positions, and yours will be different.

The code below is taken directly from IKDemo.py

from IKSolve import IKSolve

# Servo Home Values (degrees) - ***YOURS WILL DIFFER***
# ru_home = 50   # Right leg upper joint home position (servo_angle[0])
# rl_home = 109   # Right leg lower joint home position (servo_angle[1])
# lu_home = 52   # Left leg upper joint home position (servo_angle[2])
# ll_home = 23   # Left leg lower joint home position (servo_angle[3])
 
ik_handler = IKSolve(ru_home=50, rl_home=109,  # Pass home positions to IK class
                     lu_home=52, ll_home=23)  

The class can also be initialised with different leg length segments but these are best left to default unless you have changed the length of any of the leg components.

def __init__(self, ru_home, rl_home, lu_home,  
                 ll_home, upper_leg=92, lower_leg=75):

To recieve suitable angles for each servo to move to (x, y) you must use translate_xy(self, x, y, flip=False) (Flip inverts the direction that the legs bend, by default this should be set False)

  x = int(input('x:'))
  y = int(input('y:'))
  servo_angle = ik_handler.translate_xy(x, y, flip=False) 
  # The angles calculated are stored in a tuple E.g. servo_angles[0-3]
  # You can pass these values to your servo controller code

Here are the mathematical equations that were calculated for MABELs inverse kinematics, and are expressed in the translate_xy() function in IKSolve. A is used for calculating angles for the top servos (mounted to the BodyPanel) B is used to calculate angles for the ‘Knee’ servos. Upper represents the distance of the UpperLeg from pivot to pivot and lower represents the distance between the LowerLeg pivot and centre of the wheel (motor shaft).

Driving controls

MABEL is designed to work by listening to commands on the Arduino (PID contoller) end that are sent to it by the raspberry pi over serial (using pySerial). This allows easy control using bluetooth and web based solutions that are much more difficult to get working on an Arduino. The code snippets below show how you could modify/write your own controller code by sending specific bytes over serial to the arduino and YABR based firmware.

In order to use serial commands to drive MABEL around, you first need to find what serial port that the USB connection between the raspberry pi and arduino is called. In my case it was /dev/ttyACM0 but yours could be different. To find what serial port your arduino is connected to, type ls /dev/tty* into the terminal without the arduino connected. Then reconnect the arduino, run ls /dev/tty* again, and make a note of which serial port appears to be listed that was not previously there - this is your serial port.

Once you know what serial port the arduino is connected on, you should initialise the serial class with it:

import serial
from struct import pack
from time import sleep

ser = serial.Serial(port='/dev/ttyACM0', # ls /dev/tty* to find your port
		baudrate = 9600,
		parity = serial.PARITY_NONE,
		stopbits = serial.STOPBITS_ONE,
		bytesize = serial.EIGHTBITS,
		timeout = 1)

The YABR code on the arduino accepts bytes [0, 1, 2, 4, 8] as driving input commands, with 0b00000000 being ‘No movement/ remain stationary’:

# sendByte code
# 00000000 - Do nothing
# 00000001 - Turn left
# 00000010 - Turn right
# 00000100 - Move forwards
# 00001000 - Move backwards

We can then send these bytes over the serial connection, and tell MABEL in which direction to move - Here’s an example of how to write to the arduino serial port, with a bit of controller pseudocode for clarity:

while True:
    sendByte |= 0b00000000 
    if controller.direction == 'LEFT': # Controller pseudocode 
        sendByte |= 0b00000001 # This could be any sendByte
    val = pack("B", sendByte)
    ser.write(val) # Send the value over to the arduino 
    sleep(0.04) # Sleep for this period before sending next command

Contact/Support

Thanks for taking an interest in MABEL and its development! If you have any questions or need information whilst building MABEL, please feel free to mention me on twitter @raspibotics or send me an email at raspibotics@gmail.com. Whilst this page is still undergoing development, you can find updates and more information on my blog https://raspibotics.wixsite.com/pibotics-blog, where I have been posting about the development of MABEL.