0% found this document useful (0 votes)
43 views52 pages

Bicycle

This thesis presents the development of an autonomous robot bicycle designed for active safety testing in autonomous driving technology. The bicycle is equipped with sensors and actuators to follow predefined trajectories and simulate interactions with other road users, excluding human drivers for safety. Key components include a state estimator using sensor fusion, a speed-dependent controller, and an Iterative Learning Controller to enhance trajectory tracking performance, detailed across three included papers.

Uploaded by

2022ee385
Copyright
© © All Rights Reserved
We take content rights seriously. If you suspect this is your content, claim it here.
Available Formats
Download as PDF, TXT or read online on Scribd
0% found this document useful (0 votes)
43 views52 pages

Bicycle

This thesis presents the development of an autonomous robot bicycle designed for active safety testing in autonomous driving technology. The bicycle is equipped with sensors and actuators to follow predefined trajectories and simulate interactions with other road users, excluding human drivers for safety. Key components include a state estimator using sensor fusion, a speed-dependent controller, and an Iterative Learning Controller to enhance trajectory tracking performance, detailed across three included papers.

Uploaded by

2022ee385
Copyright
© © All Rights Reserved
We take content rights seriously. If you suspect this is your content, claim it here.
Available Formats
Download as PDF, TXT or read online on Scribd
You are on page 1/ 52

thesis for the degree of licentiate of engineering

An autonomous robot bicycle for active safety


tests

Yixiao Wang

Department of Electrical Engineering


Chalmers University of Technology
Gothenburg, Sweden, 2024
An autonomous robot bicycle for active safety tests

Yixiao Wang

Copyright © 2024 Yixiao Wang


All rights reserved.
The content included in this thesis may be reorganized or directly reused in
future publications.

Technical Report No. 1111-111X


ISSN 3.1415-9265
This thesis has been prepared using LATEX.

Department of Electrical Engineering


Chalmers University of Technology
SE-412 96 Gothenburg, Sweden
Phone: +46 (0)31 772 1000
www.chalmers.se

Printed by Chalmers Digital Printing


Gothenburg, Sweden, August2024
Abstract
With the rapid emergence of autonomous driving technology, safety tests have
become crucial for validating the functionality of these systems. High-fidelity
scenarios of the tests typically involve various types of road users. To ensure
safety during tests, human drivers are excluded, and instead, dummies and
robots are used to simulate real road users. The test objects should follow
pre-defined trajectories timely, and interact with each other. Then the on-
board ADAS systems’ reaction may be tested in a controllable and repeatable
manner. In this thesis, we developed an autonomous robot bicycle to serve
in the aforementioned safety tests. To build the robot, an electric bicycle
has been modified with sensors and actuators, and the target is to follow a
specified trajectory with a dummy cyclist mounted on the saddle.
Several modules are essential for this purpose. Firstly, a state estimator is
designed to compute the bicycle’s states using sensor fusion techniques. Sec-
ondly, a speed-dependent controller is developed through system identification
technique, which estimates the dynamics of the unstable bicycle based on ex-
perimental data. Finally, an Iterative Learning Controller (ILC) is designed
to exploit the repetitive nature of safety tests, enhancing trajectory track-
ing performance through iteration. These modules are detailed in the three
papers included in this thesis.
In the first paper on state estimation, we developed a Kalman-based sta-
tionary filter to estimation the bike position, speed, heading, roll and steering
angles, which are crucial for balancing and trajectory tracking. The estimator
integrates data from 4 sensors: an IMU, a steering encoder, a longitudinal
speed sensor and GPS, along with predictions results from physical models.
To evaluate this estimator, we integrated it into the control loop, and the
experimental results were consistent with our observation.
The second paper addresses the design of a speed-dependent controller
through gray-box identification. To balance the bicycle in a large speed range,
a speed-dependent gain-scheduling controller is developed based on an iden-
tified bicycle model. We proposed a method to identify such a semi-linear
model, which is nonlinear only with respect to longitudinal speeds. This
method leverages knowledge of the bicycle’s physical model structure and
collects data in a closed-loop. Experimental results demonstrate that the
controller can extrapolate the dynamics beyond known speed configurations.
The third paper discusses the iterative learning control technique for tra-
jectory tracking. The ILC evaluates longitudinal and lateral errors during
trajectory tracking experiments and computes time and position-dependent
feedforward signals to compensate for errors and unmodeled dynamics. Simu-
lation results show that errors are reduced in the both dimensions, improving
tracking performance through repetition.

Keywords: Kalman filter, System identification, Gain-scheduling control,


Iterative learning control

ii
List of Publications
This thesis is based on the following publications:

[A] Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg, “Closed loop gray box
identification of a self-balancing bicycle and its application on a gain-scheduling
controller”. Accepted by 16th International Symposium on Advanced Vehicle
Control AVEC’24 .

[B] Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg, “A Kalman filter-based


leaning, heading and position estimation for a bicycle robot”. In preparation
for submission.

[C] Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg, “Iterative learning tra-
jectory tracking control of an autonomous bicycle”. Accepted by 16th Inter-
national Symposium on Advanced Vehicle Control AVEC’24 .

iii
iv
Acronyms

ILC: Iterative Learning Control

LQR: Linear Quadratic Regulator

LMI: Linear Matrix Inequality

MPC: Model Predictive Control

MIMO: Multiple-Input-Multiple-Output

PID: Proportional-Integral-Derivative controller

SMC: Sliding Mode Control

SIDO: Single-Input-Single-Output

v
Contents

Abstract i

List of Papers iii

Acronyms v

I Overview 1
1 Introduction 3
1.1 Topics not covered by the thesis . . . . . . . . . . . . . . . . . . 5
1.2 Contributions: . . . . . . . . . . . . . . . . . . . . . . . . . . . 5
1.3 Thesis Outline . . . . . . . . . . . . . . . . . . . . . . . . . . . 6
1.4 Notation . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 6

2 Bicycle Dynamics 9
2.1 Steering-uncontrolled model . . . . . . . . . . . . . . . . . . . . 10
Assumptions . . . . . . . . . . . . . . . . . . . . . . . . . . . . 11
Applications of the Meijaard Model . . . . . . . . . . . . . . . . 11
2.2 Steering-controlled model . . . . . . . . . . . . . . . . . . . . . 12
Additional Assumptions . . . . . . . . . . . . . . . . . . . . . . 14
Application of the point-mass model . . . . . . . . . . . . . . . 14

vii
3 Bicycle robot 15
3.1 Actuators . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 15
Steering Motor . . . . . . . . . . . . . . . . . . . . . . . . . . . 16
Drive Motor . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 16
3.2 Sensors . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 17
Steering angle encoder . . . . . . . . . . . . . . . . . . . . . . . 17
Inertial Measurement Unit (IMU) . . . . . . . . . . . . . . . . . 18
GPS . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 21
Wheel speed sensor . . . . . . . . . . . . . . . . . . . . . . . . . 21
3.3 Microcontroller . . . . . . . . . . . . . . . . . . . . . . . . . . . 22
3.4 Control algorithms . . . . . . . . . . . . . . . . . . . . . . . . . 22
Motion control loops . . . . . . . . . . . . . . . . . . . . . . . . 23
State Observer . . . . . . . . . . . . . . . . . . . . . . . . . . . 25

4 Summary of included papers 29


4.1 Paper A . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 29
4.2 Paper B . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 30
4.3 Paper C . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 31

5 Concluding Remarks and Future Work 33

References 35

II Papers 41

A Gray Box Identification of a self-balancing bicycle A1


1 Introduction . . . . . . . . . . . . . . . . . . . . . . . . . . . . . A3
2 Method . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . A4
2.1 Control problem formulation . . . . . . . . . . . . . . . A5
2.2 Bicycle Models . . . . . . . . . . . . . . . . . . . . . . . A7
2.3 Experiment design and Data Collection . . . . . . . . . A8
2.4 Gray-box identification: Complex curve fitting for a
semi-linear system . . . . . . . . . . . . . . . . . . . . . A12
3 Identification and Gain scheduling controller Design . . . . . . A15
4 Experimental results . . . . . . . . . . . . . . . . . . . . . . . . A16
4.1 Gain-scheduling controller performance . . . . . . . . . A16

viii
4.2 Lower speed performance . . . . . . . . . . . . . . . . . A18
5 Conclusion . . . . . . . . . . . . . . . . . . . . . . . . . . . . . A18
References . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . A19

B Kalman filter-based leaning, heading and position estimation B1


1 Introduction . . . . . . . . . . . . . . . . . . . . . . . . . . . . . B3
2 Problem formulation and models . . . . . . . . . . . . . . . . . B6
2.1 Problem formulation and Nomenclature . . . . . . . . . B6
2.2 Bicycle models in planar motion and roll . . . . . . . . . B9
2.3 Sensors and measurement equations . . . . . . . . . . . B11
3 Multi-rate Stationary Kalman Filter . . . . . . . . . . . . . . . B21
3.1 Linearized system model . . . . . . . . . . . . . . . . . . B21
3.2 Measurement model . . . . . . . . . . . . . . . . . . . . B22
3.3 Stationary Kalman filter . . . . . . . . . . . . . . . . . . B23
4 Results . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . B24
4.1 Step-wise roll tracking . . . . . . . . . . . . . . . . . . . B25
4.2 Zero roll tracking . . . . . . . . . . . . . . . . . . . . . . B28
5 Conclusions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . B29
References . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . B32

C Iterative learning trajectory tracking control C1


1 Introduction . . . . . . . . . . . . . . . . . . . . . . . . . . . . . C3
2 Method . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . C4
3 Result . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . C8
4 Conclusions . . . . . . . . . . . . . . . . . . . . . . . . . . . . . C8
References . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . C10

ix
Part I

Overview

1
CHAPTER 1

Introduction

As an emerging technology for the future, autonomous driving has seen rapid
advancement in recent years. A critical component of this field is Advanced
Driver Assistance Systems (ADAS), where ensuring safety is paramount. Given
the complex interplay of multiple sensors and algorithms in ADAS, compre-
hensive active safety testing is vital for validating system functionality and
performance [1].
In the European New Car Assessment Program (Euro NCAP), various ac-
tive safety modules are tested. These modules include Autonomous Emer-
gency Braking (AEB), Forward Collision Warning (FCW), Emergency Steer-
ing Support (ESS), and Emergency Lane Keeping (ELK). The tests are di-
vided into several scenarios to evaluate the vehicle’s response in different situ-
ations involving cyclists, including nearside, farside, longitudinal, and turning
collisions. Each scenario assesses the vehicle’s ability to detect and react to
cyclists, aiming to reduce or avoid collisions through braking or steering in-
terventions [2].
Although engineers and scientists have developed standard test scenarios
to accurately emulate real-world conditions, achieving repeatability in these
tests remains challenging due to their complexities [3]. Established commer-

3
Chapter 1 Introduction

cial solutions, such as those from Humanetics and 4activeSystems, address


this issue by using bicycle and cyclist dummies mounted on moving platforms
(lower riders). These dummies mimic human radar reflection and visual fea-
tures, while the moving platforms can move quickly and support heavy vehicles
[4] [5]. Another solution proposed by [6] involves using balloon materials for
the dummies.
While these solutions can deliver repeatable test scenarios, they present
several challenges. Dummy bicycles made from different materials may not
accurately replicate real perception features, and the stable motion of lower
riders does not behave like real cyclists. For instance, when turning to one
direction, the dummy-lower rider solution may behave differently in wheel
spinning speeds and handlebar steering angles. This is because the dummy
wheels and handlebar, hanging in the air, lack the motion constraints pro-
vided by the road. Research indicates, at lower speeds and for normal tasks,
human riders mainly use steering motion for balancing[7], [8]. While at higher
speeds, skilled human riders can use more body lean control for balancing[9].
Given these challenges, our approach focuses on achieving more realistic bicy-
cle motion, ensuring that the movements of the robot bicycle and the dummy
more accurately mimic those of an actual cyclist.
To address these differences, we have developed an autonomous bicycle
robot, modified from a real electric bicycle with self-balancing capabilities.
We believe that if we actuate in the same manner as a human rider does, i.e.,
using steering angle adjustments and propulsion, we can create a robot that
more closely replicates the behavior of a real cyclist.
The robot’s functionality can be divided into two parts: sensing and actua-
tion. In the sensing part, hardware like GPS, speed sensor, IMU and steering
encoder are employed. An algorithm was developed to enable sensor fusion,
which estimates the necessary states for different tasks. In the actuation
part, steering and drive motor are used. The control algorithms compute the
reference signals for the motors to accomplish balancing and trajectory track-
ing tasks. This structure is visualized in Fig. 3.1 and detailed introduction is
given in chapter 3. This thesis delves into the development of the autonomous
bicycle robot, detailing both its hardware and software aspects. Aimed at the
necessary sensing and actuation, our papers covers the following problems:

• Efficient estimation of the bicycle robot’s crucial states using different


sensors (Paper B).

4
1.1 Topics not covered by the thesis

• Strategies for identifying bicycle dynamics at different speeds and meth-


ods to maintain bicycle balance at different speeds through steering (Pa-
per A).
• Trajectory tracking control to follow a motion profile precisely and timely
(Paper C).

1.1 Topics not covered by the thesis


However, certain aspects are outside the scope of this thesis:
• Longitudinal acceleration effects on the bicycle. We assume slow varia-
tion in longitudinal speed.
• Dynamics of lower-level sensors and actuators, such as steering and drive
motors. We assume the bicycle’s dynamics are much slower than those
of the electronics.
• Self-balancing capabilities of an uncontrolled steering bicycle. We refer
to [10] for detailed discussion.
• Path-tracking control of the bicycle. It has been studied by our colleague
[11].
• The software implementation of the algorithms and hardware drivers.
• Additional assumptions outlined in section 2.2.

1.2 Contributions:
Our work primarily contributes to state estimation and motion control within
the autonomous bicycle domain. We designed state estimator, effectively
tracking eight different states by accounting for sensor properties. This en-
ables precise control and state monitoring. Additionally, we develop a gain-
scheduled balancing controller by employing system identification techniques,
allowing for dynamic modeling that accounts for variations in longitudinal
speed. The practicality and accuracy of our model are demonstrated through
its application in controller design and other control-related tasks. Lastly, we
designed a trajectory tracking to improve the tracking performance through
experimental repetition.

5
Chapter 1 Introduction

Control Box
(MyRIO,
Steering Motor Driver, Emergency
GPS) Stop GPS Antenna

Steering Motor
and Encoder

Drive Motor

IMU
Drive Motor Driver
Battery Speed Sensor

Figure 1.1: The bicycle robot

1.3 Thesis Outline


To provide an overview of the physical models in our work, Chapter 2 discusses
the roll dynamics of the bicycle. Chapter 3 introduces our development of the
bicycle robot, detailing both hardware and software components. The robot
serves as the platform for validating aforementioned algorithms.

1.4 Notation
The following table compiles the key notations used in this thesis, aiding in
understanding the technical content. Most of the variables listed in the table
have been visualized in Fig. 1.2, 1.3, 1.4.

6
1.4 Notation

Figure 1.2: Bike schematics in lateral view

Figure 1.3: Bike schematics in Figure 1.4: Bike schematics for


bird view the cornering sce-
nario

7
Chapter 1 Introduction

Table 1.1: Nomenclature

a horizontal distance between the rear wheel


contact point and the center of the mass
b Bike wheelbase
c Bicycle trail
CoM Center of the Mass
hCM Height of the bike center of the mass(CoM )
[12]
δ Steering angle
φ Bike body assembly Roll angle
λ Caster angle
vf , vg , vr speed of the front wheel, GPS antenna and
rear wheel
ρf , ρg , ρr radius of path curvature of the front wheel,
GPS antenna and rear wheel
ψ Yaw angle of the bike body
θf , θg , θr the courses of front wheel, GPS antenna and
rear wheel
{i}
Xf X position of the front wheel in an arbitrary
frame {i}
{i}
Yf Y position of the front wheel in an arbitrary
frame {i}
{i}
Xg X position of the GPS antenna in an arbi-
trary frame {i}
{i}
Yg Y position of the GPS antenna in an arbi-
trary frame {i}
{i}
Xr X position of the rear wheel in an arbitrary
frame {i}
{i}
Yr Y position of the rear wheel in an arbitrary
frame {i}
δ0 the bias in steering angle reading from the
encoder

8
CHAPTER 2

Bicycle Dynamics

In this chapter, we delve into the dynamics of bicycles, an essential aspect


of autonomous bicycle technology. Both our controllers and state estimator
determines the control actions or states based on a bicycle model. Hence
choosing appropriate models will improve their performance. Our discussion
is grounded in an extensive review of the literature, with a particular emphasis
on key publications such as [10] and [13]. A brief comparison is made and then
our choice of model is motivated. Additionally, we integrate insights from more
recent research to provide a comprehensive understanding of the topic.
Historical Development of Bicycle Dynamics: The journey of bicycle dy-
namics began with the invention of the velocipede by von Drais in 1817,
characterized by ground-stepping propulsion. Lallement’s 1866 innovation of
cranks propelled the front wheel via the rider’s feet. By the 1890s, mod-
ern bicycle design had emerged, incorporating features like rear-wheel chain
propulsion and pneumatic tires. Concurrently, the study of bicycle dynamics
evolved, beginning with Rankine’s 1869 qualitative exploration of counter-
steering. [14] The subsequent years witnessed significant advancements, in-
cluding Bourlet’s 1899 simple nonlinear dynamic models, the single point
mass models by Bouasse and Boussinesq, [15], [16] and the foundational lin-

9
Chapter 2 Bicycle Dynamics

earized dynamical equations by Whipple and Carvallo around 1897-1900.[17],


[18] These early models laid the groundwork for contemporary understanding
and were instrumental in revealing the bicycle’s speed-dependent self-stability
properties. Since then, further studies have investigated the gyroscopic effect,
generalization of front fork mass distribution, and modes of motion. Sharp
[19] identified the capsize, weave, and wobble modes in 1971. In 2005, [20]
discussed a simplified bicycle model with controlled steering, assuming ideal
steering control and thereby eliminating steering dynamics. The simple point-
mass model resembles a second-order inverted pendulum in dynamics. In 2007,
[13] presents a canonical linearized form of Whipple bicycle model, with four
rigid and hinged parts. The model is able to explain the self-stability and
benchmark tests are conducted.
We will first discuss the Whipple-based model from [13] and then the sim-
plified model from [20]. They have been widely used in the community and
represent two most prevalent type of model of bicycles. The former model
requires 17 parameters but may offer more insights, whereas the latter may
be convenient for control applications due to its simplicity of demanding 5
parameters, despite evident shortcomings in self-stabilization interpretation
and others. The assumptions made during their derivation will be explicitly
listed.

2.1 Steering-uncontrolled model


Our focus now shifts to the Meijaard Model derived in [13], a comprehensive
representation based on Whipple’s model. This model conceptualizes the bi-
cycle as four interconnected rigid parts: the front and rear wheels, fork and
handlebar assembly, and rear body assembly. Each part is modeled with its
unique mass distribution. The model necessitates a total of 25 design pa-
rameters, which can be reduced to a minimum of 17. The Meijaard Model is
defined mathematically as:

M q̈ + vC1 q̇ + [gK0 + v 2 K2 ]q = f (2.1)

where q = [φ, δ]T is the vector containing the roll and steering angle, while
f = [Tφ , Tδ ]T represents external torques in consistent dimensions. v denotes

10
2.1 Steering-uncontrolled model

the longitudinal speed. The remaining constant matrices M, C1 , K0 , K2 are


calculated based on the 25 design parameters. A benchmark model is provided
in [13], with several other models available in subsequent work. The methods
for estimating inertias are introduced in [21]–[23]. For a static longitudinal
speed v, the model is linearized. However, changes in setpoint v may affect
the self-stability property, and three motion modes— weaves, capsize, and
castering— are identified to govern different speed ranges, as illustrated in
Fig. 3 in [13]. The system exhibits three degrees of freedom in the roll,
steering, and longitudinal speed dimensions, suggesting the requirements for
actuation design in control applications.

Assumptions
Despite its higher complexity compared to point-mass models to be introduced
later, the Meijaard Model makes several critical assumptions:
• Ideal hinge connections between the bicycle’s parts with negligible fric-
tion.
• Lateral symmetry in bicycle design and circular symmetry in wheels.
• The motion of the rider is assumed to be negligible in relation to the bike
body. Additionally, the model does not consider the rider’s flexibility or
control reflexes.
• All bicycle parts are treated as rigid, with no allowance for structural
compliance or the presence of dampers.
• No tire model with compliance and slip, nor tire deformation.
• Knife-edge rolling wheels with point contact, in contrary to the contact
with toroidal wheels for motorcycles.
• External forces limited to conservative gravity forces and torques f =
[Tφ , Tδ ]T , making the entire system conservative and without dissipative
forces.

Applications of the Meijaard Model


As a prevalent model, the Meijaard Model has been employed in various con-
trol applications, offering insights into bicycle dynamics and control system

11
Chapter 2 Bicycle Dynamics

design: In [24], the wobble mode of the bicycle with cyclist is studied based on
the model. In [25], a simulator is developed with lateral dynamics computed
according to the model. [26] analyses the impacts of different electric bicycle
design on the self-stability property and suggested the bicycle configurations
for cycling comfort enhancement. In [27], a MIMO LQR controller is designed
for tracking yaw and longitudinal speed. In [28], an LQR controller with in-
tegral actions and a Linear Matrix Inequality (LMI)-based observer for roll
tracking is developed, using the longitudinal speed as a scheduling parameter.
In [29], a fuzzy-logic controller for path-tracking is designed with the help of
a nonlinear system identification technique with the numerical Gauss-Newton
method. In [30], a sliding-mode controller is designed with an identified model,
achieving greater robustness than PID controllers. [31] presents a multi-loop
controller for tracking path references. In [32], a fuzzy controller is designed
based on the Lyapunov stability criterion. [33] develops a robust controller
for a motorcycle using quantitative feedback theory.

2.2 Steering-controlled model


In the first part of [20], a simplified model is derived, hereafter referred to as
the point-mass model. This model assumes ideal control of steering angular
rate and longitudinal speed, which can be used as control inputs for stabilizing
the system, making its dynamics resemble an inverted pendulum. In the
paragraph before the equation (1) in [20], the angular momentum of the bicycle
in roll direction is referred to as:
dφ dφ vD
Lx = J − Dω = J − δ, (2.2)
dt dt b
where J is the moment of inertia of the whole bicycle in the longitudinal x-
axis, and D is the inertia product with respect to the xz axes. ω = vδ/b is the
angular velocity in vertical axis, i.e., yaw velocity. The term J dφ
dt corresponds
to the capsize mode, where the bicycle falls due to gravity. Meanwhile Dω
corresponds to the weave mode, exhibiting the coupling between the roll x-axis
and the yaw z-axis.
The time-derivative of this angular momentum Lx is

dLx d2 φ Dv dδ Dδ
=J 2 − − v̇, (2.3)
dt dt b dt b

12
2.2 Steering-controlled model

where v̇ = dvdt is the longitudinal linear acceleration. The latter two terms
describe describes the effect of variations in ω, due to either the changes in
steering angle δ or the speed v.
According to Newton’s second law, the time-derivative of angular momen-
tum dL dt in longitudinal direction should equal the sum of the torques, i.e.,
x

the gravity and centrifugal force.

time-derivative of angular momentum


z}|{
dLx mv 2 h
= mghCM sin (φ) + tan (δ) . (2.4)
dt | {z } b {z
Gravititional torque
| }
Centrifugal Force

Hence
d2 φ Dv dδ mv 2 h Dδ
J 2
− − tan (δ) = mghCM sin (φ) + v̇. (2.5)
dt b dt b b
With small angle assumptions on φ and δ:

d2 φ Dv dδ mv 2 h Dδ
J 2
− − δ = mghCM φ + v̇. (2.6)
dt b dt b b
The resulting model exhibits instability, regardless of the speed v, which
contradicts the self-balancing property extensively discussed in the context of
the Meijaard Model. By including the rotation of the center of mass of the
front wheel due to steering, the self-stabilization property can be retained, as
demonstrated in equation (14) in [20]:

d2 φ Dv dδ m(v 2 hCM − acg) sin λ Dδ


J − mghCM φ = + δ+ v̇ (2.7)
dt2 b dt b b
(2.8)

where λ is the caster angle.


We have chosen this model for our control applications. The point-mass
model match our actuator settings, i.e., controlling steering angular speeds
and longitudinal speeds. Due to the actuator on the handlebar, some steering-
roll coupling dynamics are overridden, showing different dynamics from the
aforementioned Meijaard model. Furthermore, although with a simple second

13
Chapter 2 Bicycle Dynamics

order structure, it captures the main dynamics of a bicycle, which resem-


bles an inverted-pendulum. The simplicity makes real-time control easier to
implement.

Additional Assumptions
In addition to the assumptions applicable to the Meijaard Model, several more
have been made to simplify the model further:

• The steering angular rate is the system input, thus eliminating other
steering dynamics and rendering the front assembly inertia-less.

• Contributions of trail to acceleration terms of actuation are neglected.

• The inertia are approximated as point-mass: J ≈ mh2CM and D ≈


mahCM . 1

• Wheels do not possess spin momentum.

A detailed discussion and review from a vehicle dynamics and self-stability


analysis perspective, focusing on specific reduced terms and their impacts, are
elaborated in [34] and [13].

Application of the point-mass model


A limited number of studies have adopted the point-mass model. This may
be because the point-mass model more fits control applications, with steering
dynamics and longitudinal speed dynamics neglected. [35] proposes a loop-
shaping method for tuning a cascade PID. Furthermore, they design a Model
Predictive Controller (MPC) for path-tracking [36]. [37] motivates a gain-
scheduling stationary LQR controller. [38] derives a similar bicycle model in
the form of Lagrangian equation and discusses the effect of trail. Specifically,
they note that at low speeds, a higher trail can help overcome gravity-induced
torque, leading to behavior resembling an point-mass model. This observation
forms the basis for applying a PD controller. [39] designs a P controller for
the state-space form of the point-mass model and overcomes mass imbalance
and IMU sensor misalignment using yaw dynamical models.

1 This approximation has been evaluated in A. Table. 3

14
CHAPTER 3

Bicycle robot

We have transformed a standard bicycle into a robotic platform, which has


been used to validate the algorithms presented in this thesis. The ultimate
goal is for the bicycle robot, with all functionalities enabled, to participate
in active safety tests. This chapter details our experimental setup, starting
with the hardware components, such as actuators and sensors, followed by
software elements, including control structure and specifications. Lastly, we
address practical considerations and their alignment with theoretical assump-
tions listed in the previous chapter.
Fig. 3.1 illustrates the hardware connections: Four sensors on the left relay
measurement data to the microcontroller. This raw data is processed by a
state estimator, whose output is then utilized by the controller to generate
the control signals. These signals direct the actuators on the right and are
also fed back into the state estimator for state prediction or dead-reckoning.

3.1 Actuators
The modified bicycle is equipped with two actuators. These actuators align
with the degrees of freedom defined in the bicycle models of [13] and [20]. One

15
Chapter 3 Bicycle robot

motor manages the steering, while the other regulates longitudinal speeds.
This setup mirrors the approach human cyclists use for balancing, if we dis-
regard the lateral motions made by their upper bodies.

Steering Motor
We selected a graphite brushed motor, Maxon® DCX32L GB KL 24V, paired
with a gearbox GPX32HP at a 111:1 gear ratio. A timing belt transfers the
rotation to the handlebar, as depicted below. For control, a Maxon® ESCON
50/5 servo motor controller is utilized. During experiments, the steering angu-
lar rate is capped at 1 rad/s for safety, and the motor controller’s maximum
current is set to 5 A. Despite the high resolution of the motor-gearbox as-
sembly (approximately 1110.9
≈ 8.1 × 10−3◦ ), as per the datasheet, the timing
belt under load exhibits a substantial backlash of about 5◦ . This backlash
introduces uncertainty in encoder readings and challenges in controlling the
bicycle, particularly during steering direction changes.1

Assumption

The ESCON® 50/5 controller operates at a sampling rate of 53.6 kHz, well
above the balancing controller’s 100 Hz rate. Thus, we assume that the steer-
ing motor control is sufficiently rapid to meet the requirements of the point-
mass model. This model presupposes ideal steering angular rate control with
negligible steering dynamics.2 However, this assumption might not hold at
low speeds, where higher torque and larger steering actions are needed, due
to the motor’s current (torque) and speed limitations.

Drive Motor
We selected a brushless DC motor, Crystalyte® HS 2440, for longitudinal
propulsion. To regulate speed consistently, the VESC® 6 MkVI motor con-
troller was chosen. This motor operates without sensors, relying on back EMF
signals processed by the VESC® for rotor state estimation.

1 Refer to the discussion in section 4.1 of B


2 In line with the point-mass model assumptions discussed in section 2.2

16
3.2 Sensors

Different Mountings

The drive motor’s mounting varies based on the motor type, with options
including the front wheel, mid-pedal area, or rear wheel. Fig. 3.3 illustrates
both front and rear mounting configurations. For applications requiring high
torque, we recommend the rear wheel mounting due to its superior structural
strength. The longitudinal speeds at these various points can be converted
according to equations (B.6) and (B.4).

Assumption

Given the relatively slow dynamics of the bicycle, we assume the rear wheel
speed, vr , remains constant during experiments. However, this assumption
might be less valid at lower speeds. Moreover, when the drive motor is
mounted on the front wheel, a large steering angle, δ, can affect the rear
wheel speed.

Challenge

A notable challenge is the diminished and infrequent back EMF signal at low
motor speeds, inherent in sensorless control strategy. This issue compromises
control accuracy, particularly in low-speed or high-torque conditions, prompt-
ing consideration of sensored BLDC motors for improved performance in these
scenarios.

3.2 Sensors
This section describes the sensors implemented on the bicycle. Throughout
our experiments, these sensors capture measurements of steering angle, roll
angle (and rate), bike position, longitudinal speed, and heading. A Kalman
filter, designed by us, integrates these measurements to refine state estima-
tions.

Steering angle encoder


We chose the Maxon® HEDS 5540 incremental encoder for its high mea-
360
surement resolution, approximately 500×111 ≈ 0.0065◦ in steering angle. It

17
Chapter 3 Bicycle robot

is mounted on the steering motor, as depicted in Fig. 3.2. The encoder’s


mathematical model is detailed in (B.25).

Challenge

The high-ratio gearbox introduces significant challenges, effectively imped-


ing direct absolute position measurement due to its generation of 111 index
pulses per handlebar revolution. As a result, each initialization of the con-
trol program resets the current steering angle to zero, introducing an inherent
constant bias in the encoder readings. Furthermore, backlashes from the belt
transmission contribute to encoder bias as well. To address this, we have in-
corporated a state steering offset in our Kalman filter for bias correction (see
(B.26)).

Inertial Measurement Unit (IMU)


For pose estimation, we employ the cost-effective Digilent® Pmod NAV IMU,
mounted near the bicycle’s center. It provides three-axis measurements of
accelerations and angular speeds. The IMU’s measurement model is outlined
in (B.16).

Challenge

The primary challenges with the IMU are the signal-to-noise ratio (SNR)
of the accelerometer and gyroscope data, and electromagnetic interference
(EMI) from the motors. The accelerometer data, particularly susceptible to
noise when the bicycle encounters bumps, contrasts with the relatively stable
gyroscope readings. These imperfections underscore the need for a sensor
fusion approach in estimation, as briefly discussed in section 3.2.
Another issue is the calibration of the IMU’s mounting. Economical IMUs
often suffer from misalignment between their measurement axes and the ge-
ometric axes, as well as biases in accelerometer and gyroscope outputs. To
address accelerometer biases, we devised a simple calibration method under
specific assumptions. The bicycle is positioned upright, aligning actual accel-
erations to [ax , ay , az ] = [0, 0, g]. Misalignment and biases are then compen-
sated for by calculating roll (X-axis) and pitch (Y-axis) rotations. The steps
below detail the process of transforming IMU measurements (am m m
x , ay , az ) into

18
3.2 Sensors

the bicycle’s local frame accelerations (ax , ay , az ), along with the calculation
of misalignment angles φ0 and θ0 :

• We assume the IMU’s three axes are orthogonal to each other and that
the IMU is mounted at the geometric center of the bicycle, aligning
the IMU’s x-axis with the bike’s longitudinal plane. This necessitates
placing the IMU at the bicycle’s lateral center, with its X-axis pointing
forward. Consequently, the remaining misalignment between the bicy-
cle’s body axis and the IMU can be described as a combination of roll
(X-axis) and pitch (Y-axis) rotations.

• The misalignment in pitch (Y-axis) rotation from the IMU axis to the
bicycle body axis is denoted as θ0 .

• The misalignment in roll (X-axis) rotation from the IMU axis to the
bicycle body axis is denoted as φ0 .

• With the superscript m indicating the IMU measurements, the IMU


acceleration measurements [am m m
x , ay , az ] can be transformed into bicy-
cle local frame accelerations [ax , ay , az ] through roll-pitch rotations, as
shown in the following equations:
   m
ax ax
ay  = Rx (φ0 )Ry (θ0 ) am
y
 (3.1)
m
az az
 
1 0 0
Rx (φ0 ) = 0 cos (φ0 ) − sin (φ0 ) (3.2)
0 sin (φ0 ) cos (φ0 )
 
cos (θ0 ) 0 sin (θ0 )
Ry (θ0 ) =  0 1 0 . (3.3)
− sin (θ0 ) 0 cos (θ0 )

Rx (φ0 ) and Ry (θ0 ) are the rotation matrices in x-axis and y-axis, re-

19
Chapter 3 Bicycle robot

spectively. More conveniently,

ax = cos (θ0 )am m


x + sin (θ0 )az (3.4)
ay = cos (φ0 )am m m
y + sin (φ0 )(sin (θ0 )ax − cos (θ0 )az ) (3.5)
ax = sin (φ0 )am m m
y + cos (φ0 )(cos (θ0 )az − sin (θ0 )ax ) (3.6)
(3.7)

• To compute the misalignment angles φ0 and θ0 , we maintain the bicycle


in an upright position, ensuring the acceleration in the bicycle body
frame is approximately [ax , ay , az ] = [0, 0, g]. These angles can then be
estimated using the measured accelerations [am m m
x , ay , az ]:

aˆm
y
φ0 = arctan q (3.8)
2
aˆm ˆm 2
x + az

aˆm
x
θ0 = arctan q (3.9)
2
aˆm ˆm 2
y + az

(3.10)

Sensors for roll estimations


The IMU is primarily employed for estimating roll, a critical parameter for
maintaining balance. Various algorithms have been developed for roll estima-
tion, each with unique advantages and limitations. This summary highlights
literature on roll estimation techniques, focusing on methods beyond IMU
measurements.
Researchers have investigated diverse strategies for determining roll angle.
In [40], a specially designed trailer attached to the bicycle provides absolute
roll measurement by tracking its relative motion. Optical systems, with or
without reflective markers, are another approach for roll angle measurement,
as discussed in [41], [42]. Distance sensors mounted on either side of the
bicycle, as explored in [43], [44], offer an alternative method. [45] utilizes
gyroscope readings from Y (lateral) and Z (vertical) axes in a Kalman filter-
based complementary approach. This study proposes two models for roll angle
estimation under varying assumptions: the bicycle in steady-state cornering
and negligible pitch rate. In [46], a comparison is made between accelerometer

20
3.2 Sensors

and gyroscope-based IMU measurements and a visual approach.


Among these methods, IMU-based approaches are deemed the most cost-
effective, particularly with the availability of low-cost MEMS sensors. Thus,
an IMU is integrated into our electrified bicycle. For our control purposes,
correlated parameters such as roll angle φ, steering angle δ, position (X, Y ),
rear wheel speed vr , and heading ψ are essential. We designed a Kalman
filter that combines data from four sensors – GPS, steer encoder, longitudinal
speed sensor, and IMU – to estimate these states. In this filter, we employ
roll models based on gyroscope measurements from [45] and another model
utilizing accelerometer data.

GPS
We selected the Ublox® ZED-F9p GPS module to determine the bicycle’s
position. It provides longitude, latitude, speed, and course data to the mi-
crocontroller, as modeled in (B.21). With L2 signals, this GPS unit samples
data at 10 Hz.

Challenge
While the nominal GPS sampling rate is 10 Hz, the measurements can some-
times be delayed or dropped. These errors are identifiable by comparing lon-
gitude, latitude, and GPS NMEA timestamps against predicted values. We
apply a filtering technique during data acquisition in the Kalman filter process,
ensuring the reliability of the measurements.

Wheel speed sensor


We mounted nine magnets on the string of the rear wheel, which interact with
the reed proximity sensor Assemtech® MMPSA 240/100 to generate pulses.
Fig. 3.4 illustrates this setup. Using the rear wheel radius Rw and the interval
between pulses ∆Trps , we can calculate a low-pass filtered speed as per (B.14).

Challenge
A significant challenge with this speed estimation method is the occurrence
of random multi-pulses triggered by certain magnets, possibly due to their
breakage or unevenness. To address this, we adjust the sensor’s bounce time

21
Chapter 3 Bicycle robot

based on speed and implement a low-pass filter. The speed calculation in


(B.14), which averages the elapsed time over nine magnetic pulses, minimizes
this error by a factor of 91 . If the multi-pulse issue from a particular magnet
occurs systematically, we can modify (B.14) by using a different count value
instead of nine, to achieve more accurate speed estimation.

3.3 Microcontroller
For our system, we selected the NI MyRio® -1900 microcontroller to interface
with the previously mentioned sensors and actuators. Operating on a real-time
Linux system, it comprises two processing layers: FPGA and CPU. We utilize
LabVIEW to achieve a 100 Hz sampling frequency. The FPGA primarily
handles communication tasks to ensure rapid input and output speeds, while
the CPU is responsible for executing control and state-estimation algorithms.
Table 3.1 provides an overview of the communication protocols employed for
each hardware component and the respective processors involved.

Table 3.1: Communication Protocols and Processors

Hardware Communication proto- Processor


col
Steering Motor PWM FPGA
Drive Motor UART CPU
Encoder GPIO FPGA
IMU SPI FPGA
GPS UART CPU
RPS GPIO FPGA

3.4 Control algorithms


Operating at a sampling frequency of 100 Hz, both the motion controller and
the state estimator are executed within the microcontroller, as depicted in
Fig. 3.1.

22
3.4 Control algorithms

Motion control loops


Fig. 3.5 presents an overview of the path-tracking loop, while Fig. 3.6 de-
tails the cascade control loops within the roll tracking controller. In these
figures, Kouter , Kinner , Kv , and Kinner represent the controllers in various
loops. Lbike and L′bike denote the physical dynamics of roll and longitudinal
speed, respectively.
This subsection delves into each control loop depicted in Fig. 3.5 and Fig.
3.6, progressing from the highest level (path-tracking loop) to the lowest level
(steering control loop).

Path-tracking loop

The roll tracking controller generates a roll angle reference φref for following a
predefined path. Intuitively, a left (negative) roll reference steers the bicycle to
the left, and vice versa. Several algorithms are suitable for this control strat-
egy. The difference between the reference and current positions is projected
into lateral and longitudinal errors, which are then mitigated by the steering
and drive motor propulsion, respectively. The Line-of-Sight technique, com-
monly used in missile guidance, and other approaches like [11], are referenced
here. The Line-of-Sight algorithm tracks the reference by vectoring the track-
ing error and using this vector as the reference heading angle ψref . A simple
proportional (P) controller tracks this reference heading angle with the roll
reference signal φref . Conversely, [11] decomposes the error into lateral and
longitudinal components, tracking the position reference via a combination of
lateral and longitudinal position controllers. Due to the bicycle’s underactu-
ated nature, a look-ahead set-point is essential in both methodologies.
An example of the Line-of-Sight path tracking algorithm is as follows: Let
(X G , Y G ) represent the bike position (X, Y ) in the global coordinate system,
with the subscript ref indicating the reference state. At timestep T , the error
vector between the looked-ahead time ∆T reference position and the current
position is calculated as:
{G}
∆X {G} (T ) = Xref (T + ∆T ) − X {G} (T )
{G}
∆Y {G} (T ) = Yref (T + ∆T ) − Y {G} (T )

23
Chapter 3 Bicycle robot

Then the heading reference ψref is:

∆Y {G} (T )
ψref (T ) = arctan (3.11)
∆X {G} (T )

To track the heading reference, with KP as the control gain, the roll reference
is determined by:

φref (T ) = −KP (ψref (T ) − ψ(T )) (3.12)

Roll Tracking Loop


For controlling the roll reference φref , we have implemented a simple Propor-
tional (P) controller that utilizes the roll rate reference φ̇ref . The design of
both the roll tracking and the balancing loops is elaborated in Section 3.
Let KP φ denote the gain of roll tracking loop, the reference roll angular
rate φ̇ref is:
φ̇ref (T ) = KP φ (φref (T ) − φ(T )) (3.13)

Balancing Loop
The balancing loop receives the roll rate reference φ̇ref and outputs steering
rate reference δ̇ref to keep the bicycle balanced. It is designed together with
the roll tracking loop and the both of them are Proportional controller in our
application. Bandwidths are the crucial design factors, as too high bandwidth
may excite unexpected dynamics in the control loop and consequently, induce
oscillations. In practice, the author has observed an oscillation of 2.7 Hz on
the real bicycle, when the balancing control gain is too high, i.e., <> 7. The
oscillation at this frequency may relate to the weave mode of the bicycle [47],
and it was likely excited by the IMU gyroscope sensor noises. This arises
a practical limit for balancing control, especially at lower speeds where high
control gains are often required.
Let KP φ̇ be the gain in the balancing loop:

δ̇ref (T ) = −KP φ̇ (φ̇ref (T ) − φ̇(T )) (3.14)

The gain in the balancing loop, KP φ̇ , is given by:

δ̇ref (T ) = −KP φ̇(φ̇ref (T ) − φ̇(T )). (3.15)

24
3.4 Control algorithms

Steering tracking
The innermost loop in Fig. 3.6, steering control, is incorporated into the
steering motor driver ESCON® 50/5, operating a Proportion-Integral (PI)
controller at 53.6 kHz. With a PI structure hard-coded in the motor driver,
this controller tracks the steering angular speed reference δ̇ref according to the
measurement from Maxon® HED 5540 incremental encoder. Given its high
sampling frequency (53.6 kHz) relative to other loops (100 Hz), we assume
ideal tracking from the steering control loop in our experiments. To prevent
accidents, the maximum permissible steering angle is limited to 45◦ , and the
steering angular speed is limited to 1 rad/s.

Longitudinal speed tracking


The longitudinal control loop runs in the motor driver VESC® 6 MkVI. It runs
a cascade P-I control structure to track a given speed. The control structure
is pre-defined by the motor driver, with its control parameters tunable. The
measurement and error data are accessible for the microcontroller in real-time.
The motor driver also supports current tracking mode, which is of interests
in torque control applications.

State Observer
An observer processes sensor data, providing estimated states to the con-
trollers in various loops. For our path-tracking application, the primary states
are position X, Y , and roll angle φ. Additionally, speed v, roll angular rate φ̇,
heading Ψ, steering angle δ, and encoder bias δ0 are estimated to facilitate fu-
ture state predictions. Detailed information about the observer can be found
in the paper referenced in B.

25
Chapter 3 Bicycle robot

Microcontroller

IMU

Steering
Motor

RPS

Observer
GPS (Kalman Controller
Filter)

Steering
Encoder
Longitudinal
Motor

Longitudinal Motor
Driver (VESC)

Figure 3.1: Structure of the hardware

26
3.4 Control algorithms

Steering Axle
Timing Belt

Motor and gearbox


assembly

Encoder

Figure 3.2: Steering motor assembly

Rear mounting
Front mounting
Figure 3.3: Drive motor mounted at the front or the rear wheel

27
Chapter 3 Bicycle robot

Magnet × 9 Reed
Proximity
Sensor
Figure 3.4: Mounting of magnets and RPS on the wheels

Path-tracking Roll-tracking
controller Cascade loop

Kalman Filter

Figure 3.5: The path-trakcing controller in higher level

disturbances

vref ev v
Kv L′bike v

Outer roll tracking loop


Inner balancing Loop
Steering Control
φref eφ φ̇ref eφ̇ δ̇ref eδ̇ δ̇ φ̇
Kouter Kinner KSteer Lbike (v)
− − −ˆ
δ̇ δ̇ˆ
φ̂ φ̇ˆ disturbances
Kalman Filter

Figure 3.6: Schematic of the cascade control loops in roll tracking controller

28
CHAPTER 4

Summary of included papers

This chapter provides a summary of the included papers.

4.1 Paper A
Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg
Closed loop gray box identification of a self-balancing bicycle and its
application on a gain-scheduling controller
Accepted by 16th International Symposium on Advanced Vehicle Control
AVEC’24 .

This paper addresses the balancing control problem of the bicycle robot at
different speeds. Although high control gains will in general work for balanc-
ing, there are physical limits from actuators and system dynamics. Therefore
a model-based design approach will be beneficial, as it suggests lower but ap-
propriate gains. Then another problem is how to obtain a numerical model
of the bicycle robot to aid the design. We chose a data-driven approach by
applying system identification technique. Combining these strategies, this pa-
per applies a Gray-box identification technique to the robot bicycle, aiming to

29
Chapter 4 Summary of included papers

identify a semi-linear physical model to be used for designing a gain-scheduled


controller. A numerical model was first obtained through system identifica-
tion with the experimental data. Numerical values of the physical parameters
are computed according to the identified model, and then compared against
the measured ones, showing positive result. This identified model is further
used for designing a gain-scheduled controller, whose gain varies with speeds.
The gain-scheduled controller was also validated in roll tracking experiments
at different speeds.

4.2 Paper B
Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg
A Kalman filter-based leaning, heading and position estimation for a
bicycle robot
In preparation for submission .

To accomplish balancing and trajectory tracking tasks, the crucial states, in-
cluding roll angle, position, heading angle and speed are requested by the con-
troller. Four different sensors measure them at different frequencies. Hence,
sensor fusion is needed to combine the information from both the sensor mea-
surements and the known numerical models. The steering encoder bias, as a
hidden state, is also identified and included in our state estimation, which is
induced by the gearbox backlashes of the steering transmission. As a result, a
total of 8 states are estimated in this sensor fusion problem. Meanwhile, the
multi-rate sensor properties and real-time performance requirements should
be considered. By exploiting the dynamical connection between roll and posi-
tion, this paper provides a multi-rate state estimation approach in a Kalman
scheme. Thanks to this connection, the backlashes in steering transmission
is estimated and adapted to by the estimator, resulting in a more accurate
estimation and dead-reckoning performance. Since the estimator is in a sta-
tionary Kalman filter scheme, the computation complexity is much lower than
Extended Kalman filters or Particle filters, making it possible to deploy on
our microcontroller.

30
4.3 Paper C

4.3 Paper C
Yixiao Wang, Fredrik Bruzelius, Jonas Sjöberg
Iterative learning trajectory tracking control of an autonomous bicycle
Accepted by 16th International Symposium on Advanced Vehicle Control
AVEC’24 .

For effective interaction with other test objects, precise bicycle trajectory
tracking control is essential. Such control should ensure that both the progress
and the path are well managed. As feedback control is driven by the errors, its
performance is limited by the unmodelled dynamics and control constraints.
The tracking errors will consequently not be eliminated and will behave same
during the repetitive experiments. To further reduce the errors in feedback
control, feedforward is often introduced as an external reference to the con-
trol loop. In the case of repetitive control tasks, Iterative Learning Control
(ILC) further provides an approach to learn an adaptive feedforward. This
approach can exploit the repetitive feature of our control application and fur-
ther reduce the tracking errors as we repeat the experiments. In this paper,
we present a design of an ILC controller tailored for the trajectory tracking
problem of an autonomous bicycle. We have decomposed the ILC trajectory
tracking problem into a longitudinal and a lateral motion ILC tracking prob-
lems. This decomposition is based on several underlying assumptions related
to lower level controllers and no tyre side-slip. The resulting lateral controller
depends only on position, while the longitudinal ILC controller depends only
on time. To illustrate the performance of the controller, simulations have been
conducted. The positive result shows the proposed ILC controller is ready for
deployment on the real bicycle, which will be implemented in the future.

31
CHAPTER 5

Concluding Remarks and Future Work

This thesis presents the culmination of our efforts in developing a bicycle


robot, focusing on three pivotal aspects: balancing control, state estimation
and trajectory tracking control. These elements are crucial for enabling the
autonomous bicycle robot, thereby meeting the functional requirements of
active safety tests discussed in section 1.
While having addressed the four problems in the introduction section, we
could see obvious limits in our approaches. We have applied a steering to the
fall strategy for balancing the bicycle, and used a semi-linear model to describe
the bicycle dynamics. This approach does not work for too low longitudinal
speeds, in our case, speed v < 1.5 m/s. In general, lower speeds require higher
control gain. This means, higher steering angles and angular speeds will be
required given the same level of error. At some point, they will reach the power
limits of the steering motor. Furthermore, the higher gains will increase the
bandwidth of the closed loop system, requesting higher signal-to-noise ratio
(SNR) in state estimation in the corresponding frequency range. Considering
these two aspects, more investigations are needed to balance the bicycle at
low speeds.
Throughout our development process, we adapted our strategies in both

33
Chapter 5 Concluding Remarks and Future Work

hardware and software multiple times to address various practical issues.


These issues included data I/O latency, computational complexity, sensor
reading outliers, electromagnetic interference, multiple pulses in magnetic sen-
sors, and power surges in DC-DC converters. We addressed some of these
challenges through more tailored designs or by reducing system complexity.
Others were deemed negligible in the context of our control applications.As
an example, multi-thread and multi-process programming technique is used
to make the controller and state estimator work asynchronously. This helps
mitigate the impact of I/O latency.
A key lesson learned is the principle of staying simple. We designed the
controller using a simple inverted-pendulum model, which was proved suf-
ficient. The simple gain-scheduled P-D cascade control structures enabled
real-time computation at 100 Hz, and the light-weight stationary state es-
timator successfully estimated eight different states without latency. While
the economical hardware components we used exhibited limited performance,
particularly with high-frequency noises and bias, these issues were not critical
for a control problem with a bandwidth lower than 5 Hz. Trade-offs are often
necessary to address the most pressing issues effectively.
Looking ahead, our future work will investigate the influence of longitudinal
acceleration, specifically its potential to enhance the balance control at lower
speeds. By using additional longitudinal acceleration, the bicycle may better
achieve balance with the same hardware configuration. Additionally, integrat-
ing the bicycle robot into real active safety tests will present further challenges
that we must overcome. For instance, the additional computation load will
impose difficulty in the real-time implementation of the bicycle. Synchroniza-
tions and coordination between different test objects, such that all moving
objects are positioned timely, may also be challenging.

34
References

[1] H.-P. Schöner, S. Neads, and N. Schretter, “Testing and verification


of active safety systems with coordinated automated driving,” in Pro-
ceedings of the 21st (ESV) International Technical Conference on the
Enhanced Safety of Vehicles.
[2] European New Car Assessment Programme (Euro NCAP), “Euro ncap
assessment protocol - vulnerable road user protection,” Euro NCAP,
Tech. Rep., version 11.4, Dec. 2023, Accessed: 2024-07-10.
[3] H. Eriksson, J. Hérard, and J. Jacobson, “Status of test methods for
active safety systems,” SAE Technical Papers, pp. 36–0214, 2012.
[4] H. Group, Ufomicro h umanetics, Accessed: 2024-07-10, 2024.
[5] 4ActiveSystems, 4activebs - euro ncap bicyclist targets, Accessed: 2024-
07-10, 2024.
[6] Y. Park, S. Lee, M. Park, J. Shin, and J. Jeong, “Target robot for active
safety evaluation of adas vehicles,” Journal of Mechanical Science and
Technology, vol. 33, no. 9, pp. 4431–4438, 2019, issn: 1738-494X.
[7] J. K. Moore, J. D. Kooijman, A. L. Schwab, and M. Hubbard, “Rider
motion identification during normal bicycling by means of principal
component analysis,” Multibody System Dynamics, vol. 25, pp. 225–244,
2011.
[8] J. K. Moore, M. Hubbard, A. Schwab, J. Kooijman, and D. L. Peterson,
“Statistics of bicycle rider motion,” Procedia Engineering, vol. 2, no. 2,
pp. 2937–2942, 2010.

35
References

[9] S. M. Cain, J. A. Ashton-Miller, and N. C. Perkins, “On the skill of


balancing while riding a bicycle,” PLoS one, vol. 11, no. 2, e0149340,
2016.
[10] A. L. Schwab and J. P. Meijaard, “A review on bicycle dynamics and
rider control,” Vehicle system dynamics, vol. 51, no. 7, pp. 1059–1090,
2013, issn: 0042-3114.
[11] G. Wen and J. Sjöberg, “Lateral control of a self-driving bike,” in 2022
IEEE International Conference on Vehicular Electronics and Safety (ICVES),
2022, pp. 1–6.
[12] G. Starr, “Calculating motorcycle center of mass,” Me. unm. edu, 2015.
[13] J. P. Meijaard, J. M. Papadopoulos, A. Ruina, and A. L. Schwab, “Lin-
earized dynamics equations for the balance and steer of a bicycle: A
benchmark and review,” Proceedings of the Royal society A: mathemat-
ical, physical and engineering sciences, vol. 463, no. 2084, pp. 1955–1982,
2007, issn: 1364-5021.
[14] W. Rankine, “On the dynamical principles of the motion of velocipedes,”
Engineer 28 (1869), pp. 79–175, 1869.
[15] H. Bouasse, “Cours de mécanique rationnelle et expérimentale,” Li-
brairie Ch. Delagrave, Paris, 1910.
[16] J. Boussinesq, “Aperçu sur la théorie de la bicyclette,” fre, Journal de
Mathématiques Pures et Appliquées, vol. 5, pp. 117–136, 1899.
[17] F.J.W.Whipple, “The stability of the motion of a bicycle,” Q. J. Pure
Appl. Math. 30, pp. 312–348, 1899.
[18] E. Carvallo, “Théorie du mouvement du monocycle et de la bicyclette,”
Gauthier-Villars, Paris, pp. 312–348, 1899.
[19] R. S. Sharp, “The stability and control of motorcycles,” Journal of me-
chanical engineering science, vol. 13, no. 5, pp. 316–329, 1971, issn:
0022-2542.
[20] K. J. Astrom, R. E. Klein, and A. Lennartsson, “Bicycle dynamics and
control: Adapted bicycles for education and research,” IEEE Control
Systems Magazine, vol. 25, no. 4, pp. 26–47, 2005, issn: 1066-033X.
[21] J. Kooijman, “Experimental validation of a model for the motion of an
uncontrolled bicycle,” Master’s Thesis, 2006.

36
References

[22] J. K. Moore, M. Hubbard, D. L. Peterson, A. Schwab, and J. Kooijman,


“An accurate method of measuring and comparing a bicycle’s physi-
cal parameters,” in Bicycle and Motorcycle Dynamics: Symposium on
the Dynamics and Control of Single Track Vehicles. Delft, Netherlands,
2010.
[23] J. K. Moore, M. Hubbard, J. Kooijman, and A. Schwab, “A method
for estimating physical properties of a combined bicycle and rider,” in
International Design Engineering Technical Conferences and Computers
and Information in Engineering Conference, vol. 49019, 2009, pp. 2011–
2020, isbn: 0791849015.
[24] J. E. Florian Klinger Julia Nusime and M. Plöchl, “Wobble of a racing
bicycle with a rider hands on and hands off the handlebar,” Vehicle
System Dynamics, vol. 52, no. sup1, pp. 51–68, 2014.
[25] V. v. d. W. Jelle Haasnoot Riender Happee and A. L. Schwab, “Valida-
tion of a novel bicycle simulator with realistic lateral and roll motion,”
Vehicle System Dynamics, vol. 62, no. 7, pp. 1802–1826, 2024.
[26] S. Dieltiens, F. Debrouwere, M. Juwet, and E. Demeester, “Practical
application of the whipple and carvallo stability model on modern bi-
cycles with pedal assistance,” Applied Sciences, vol. 10, no. 16, p. 5672,
2020, issn: 2076-3417.
[27] D. L. Peterson and M. Hubbard, “Yaw rate and velocity tracking control
of a hands-free bicycle,” in ASME International Mechanical Engineering
Congress and Exposition, vol. 48630, pp. 447–454, isbn: 0791848639.
[28] J. A. Brizuela-Mendoza, C. M. Astorga-Zaragoza, A. Zavala-Río, F.
Canales-Abarca, and M. Martínez-García, “Gain-scheduled linear quadratic
regulator applied to the stabilization of a riderless bicycle,” Proceedings
of the Institution of Mechanical Engineers, Part I: Journal of Systems
and Control Engineering, vol. 231, no. 8, pp. 669–682, 2017, issn: 0959-
6518.
[29] T.-K. Dao and C.-K. Chen, “Path-tracking control of a riderless bicy-
cle via road preview and speed adaptation,” Asian Journal of Control,
vol. 15, no. 4, pp. 1036–1050, 2013, issn: 1561-8625.
[30] T.-K. Dao and C.-K. Chen, “Sliding-mode control for the roll-angle
tracking of an unmanned bicycle,” Vehicle system dynamics, vol. 49,
no. 6, pp. 915–930, 2011, issn: 0042-3114.

37
References

[31] D. Bickford and D. E. Davison, “Systematic multi-loop control for au-


tonomous bicycle path following,” in 2013 26th IEEE Canadian Confer-
ence on Electrical and Computer Engineering (CCECE), IEEE, pp. 1–5,
isbn: 1479900338.
[32] S. Hashemnia, M. Shariat Panahi, and M. J. Mahjoob, “Unmanned bicy-
cle balancing via lyapunov rule-based fuzzy control,” Multibody System
Dynamics, vol. 31, pp. 147–168, 2014, issn: 1384-5640.
[33] U. Nenner, R. Linker, and P.-O. Gutman, “Robust feedback stabiliza-
tion of an unmanned motorcycle,” Control Engineering Practice, vol. 18,
no. 8, pp. 970–978, 2010, issn: 0967-0661.
[34] D. J. Limebeer and R. S. Sharp, “Bicycles, motorcycles, and models,”
IEEE Control Systems Magazine, vol. 26, no. 5, pp. 34–61, 2006, issn:
1066-033X.
[35] T. Andersson, N. Persson, A. Fattouh, and M. C. Ekström, “A loop
shaping method for stabilising a riderless bicycle,” in 2019 European
Conference on Mobile Robots (ECMR), IEEE, pp. 1–6, isbn: 1728136059.
[36] N. Persson, M. C. Ekstrom, M. Ekstrom, and A. V. Papadopoulos, “Tra-
jectory tracking and stabilisation of a riderless bicycle,” IEEE.
[37] Z. Yongli, Y. Liu, and G. Yi, “Model analysis of unmanned bicycle and
variable gain lqr control,” IEEE.
[38] Y. Yu and M. Zhao, “Steering control for autonomously balancing bicy-
cle at low speed,” IEEE.
[39] C.-F. Huang, Y.-C. Tung, H.-T. Lu, and T. J. Yeh, “Balancing control
of a bicycle-riding humanoid robot with center of gravity estimation,”
Advanced Robotics, vol. 32, no. 17, pp. 918–929, 2018, issn: 0169-1864.
[40] J. K. Moore, Human control of a bicycle. University of California, Davis,
2012, isbn: 1267759720.
[41] B. Fonda, N. Sarabon, and F.-X. Li, “Bicycle rider control skills: Ex-
pertise and assessment,” Journal of sports sciences, vol. 35, no. 14,
pp. 1383–1391, 2017, issn: 0264-0414.
[42] M. Schlipsing, J. Schepanek, and J. Salmen, “Video-based roll angle
estimation for two-wheeled vehicles,” IEEE.

38
References

[43] I. Boniolo, M. Norgia, M. Tanelli, C. Svelto, and S. M. Savaresi, “Perfor-


mance analysis of an optical distance sensor for roll angle estimation in
sport motorcycles,” IFAC Proceedings Volumes, vol. 41, no. 2, pp. 135–
140, 2008, issn: 1474-6670.
[44] R. Lot, V. Cossalter, and M. Massaro, “Real-time roll angle estimation
for two-wheeled vehicles,” American Society of Mechanical Engineers.
[45] E. Sanjurjo, M. A. Naya, J. Cuadrado, and A. L. Schwab, “Roll angle
estimator based on angular rate measurements for bicycles,” Vehicle
system dynamics, 2018.
[46] M. Schlipsing, J. Salmen, B. Lattke, K. G. Schroter, and H. Winner,
“Roll angle estimation for motorcycles: Comparing video and inertial
sensor approaches,” IEEE.
[47] D. J. N. Limebeer, R. S. Sharp, and S. Evangelou, “The stability of mo-
torcycles under acceleration and braking,” Proceedings of the Institution
of Mechanical Engineers, Part C: Journal of Mechanical Engineering
Science, vol. 215, no. 9, pp. 1095–1109, 2001, issn: 0954-4062.

39

You might also like