In this build log, I am documenting a reference build of a ArduRover balancebot (Balance Bots — Rover documentation), using a Yahboom chassis kit. It’s intended as a improvement on the ArduRoller (ArduRoller Balance Bot — Rover documentation) reference build, which required a 3D printed chassis.
Required parts:
- Yahboom Chassis Kit (Self-balancing Robot Car Chassis Kit With 520 Motor Rubber Tire)
- Flight Controller + GPS
- 12V Battery (3x 18650 batteries, similar to https://core-electronics.com.au/3-x-18650-battery-holder-with-dc2-1-power-jack.html)
- Radio modules as needed
- Roboclaw 2x7A Motor controller (Pololu - RoboClaw 2x7A Motor Controller (V6B/V6F))
Hardware build
I did originally buy a ready-made 3S battery (ZOHD Lionpack 18650 3S1P 3500mAh 11.1V Li-ion Battery [DG] – Phaser FPV), but it didn’t fit well in the chassis. I instead bought a 3x 18650 battery holder and soldered the appropriate connectors. The holder fits well in the bottom box:
The flight controller was placed in the middle section. A Cube + Standard Carrier Board just fits between the vertical spacers.
The GPS and radio modules required some careful placement, as it was little cramped on the top layer. I also needed to drill a few extra holes in the top plate to allow access to the cables between them and the flight controller.
The Roboclaw motor controller (and standard power module) were mounted at the side.
For the electrical connections, I followed the diagram at ArduRoller Balance Bot — Rover documentation, except the power for the encoders came from the flight controller’s servo rail instead of the motor controller.
Motor Controller settings
The Roboclaw needed a few settings changed via the BasicMicro Motion Studio software (https://downloads.basicmicro.com/software/IonStudio/setup.exe). Note there is a (mandatory) Roboclaw firmware upgrade on initially connecting the controller. Annoyingly, this firmware upgrade requires a Windows PC/Laptop and will not work inside a VM.
Once the firmware upgrade is complete, the Motion Studio software can be used within a Windows VM for changing or viewing Roboclaw settings.
The settings to be changed are the RC limits, autocalibration, deadzone and default accel/decel:
Note RC Timeout and Safe Start need to be disabled, as I found the Roboclaw would occasionally not come out of failsafe after arming the vehicle.
ArduPilot parameters
The following parameters the support the above hardware are mostly for configuring the motor controller and wheel encoders:
Enable balancebot support:
FRAME_CLASS 3
FRAME_TYPE 0
Motor settings, assuming left motor on Servo1 and left motor on Servo2
MOT_SLEWRATE 0
SERVO1_FUNCTION 74
SERVO1_MAX 1920
SERVO1_MIN 1120
SERVO1_REVERSED 0
SERVO1_TRIM 1520
SERVO3_FUNCTION 73
SERVO3_MAX 1920
SERVO3_MIN 1120
SERVO3_REVERSED 0
SERVO3_TRIM 1520
Wheel encoder parameters, assuming left wheel encoder (WENC_) on AUX Out 5/6 and right wheel encoder (WENC2_) on AUX Out 3/4. The EKF is also configured to use the wheel encoders as a velocity source:
WENC2_CPR 1320
WENC2_PINA 53
WENC2_PINB 52
WENC2_POS_X 0.000000
WENC2_POS_Y 0.080000
WENC2_POS_Z 0.000000
WENC2_RADIUS 0.034000
WENC2_TYPE 1
WENC_CPR 1320
WENC_PINA 54
WENC_PINB 55
WENC_POS_X 0.000000
WENC_POS_Y -0.080000
WENC_POS_Z 0.000000
WENC_RADIUS 0.034000
WENC_TYPE 1
SERVO11_FUNCTION -1
SERVO12_FUNCTION -1
SERVO13_FUNCTION -1
SERVO14_FUNCTION -1
EK3_SRC1_VELXY 7
Balancebot manual tuning (pitch to throttle controller)
For manual mode, a stable pitch-to-throttle (ATC_BAL_) tune is required. This translates a desired pitch to a throttle output. It is best to think of the it as the input throttle as an input pitch, so the vehicle is trying to achieve a specific pitch angle, in order to move forward/back.
I found the tuning to be quite tricky, but the following tips helped immensely:
MOT_THST_EXPOneeds to be around -0.5, to give a stable pitch angle at both small and large pitch anglesMOT_THR_MINwas higher than expected. Despite the ~8% I observed during testing, I had to increase it up to 12% to reduce wobbling- The
ATC_BAL_PID’s needed to be far higher than the suggested range. I suspect this is due to the vehicle being quite small and very maneuverable. The PID tuning was also bit finicky, in trying to find the right values that allowed snappy movement, whilst ensuring the vehicle didn’t overcorrect and topple or have oscillations.
In doing the tuning, I found I needed to increase P and I in turn. So I increased P to reduce wobbling, until I got oscillations. I then increased I until the oscillations stopped. Once I had then reasonably dialled in, I started adding a little bit of D (in increments of 0.02) to make the robot more responsive. I sometimes needed to decrease P or increase I to remove any oscillations caused by the increased D.
In the end, the following PID’s worked well:
ATC_BAL_D 0.120000
ATC_BAL_D_FF 0.000000
ATC_BAL_FF 0.000000
ATC_BAL_I 10.000000
ATC_BAL_IMAX 1.000000
ATC_BAL_LIM_TC 0.500000
ATC_BAL_LIM_THR 1.000000
ATC_BAL_P 3.200000
ATC_BAL_PDMX 0.000000
Looking at the logged PID’s, there it still some overshoot when slowing down, but that seems to be expected for balancebots as they need to tilt opposite to their current direction to reduce their velocity. I had a persistent 2.5 degree wobble, as shown in the below graph:
Whilst the above graph may indicate a non-optimal tune, a video showing it’s movement is far less severe than one might expect.
So, that this point I have a balancebot that works fairly well in manual mode. In my next post, I’ll go through the speed and throttle tuning.




