• No results found

NAVIGATION AND PLANNED MOVEMENT OF AN UNMANNED BICYCLE

N/A
N/A
Protected

Academic year: 2021

Share "NAVIGATION AND PLANNED MOVEMENT OF AN UNMANNED BICYCLE"

Copied!
47
0
0

Loading.... (view fulltext now)

Full text

(1)

aster˚

as, Sweden

Thesis for the Degree of Master of Science in Engineering - Robotics

30.0 credits

NAVIGATION AND PLANNED

MOVEMENT OF AN UNMANNED

BICYCLE

Hampus Baaz

hbz15001@student.mdh.se

Examiner: Alessandro Papadopoulos

alardalen University, V¨

aster˚

as, Sweden

Supervisors: Niklas Persson

alardalen University, V¨

aster˚

as, Sweden

Henrik Falk

alardalen University, V¨

aster˚

as, Sweden

(2)

Abstract

A conventional bicycle is a stable system given adequate forward velocity. However, the velocity region of stability is limited and depends on the geometric parameters of the bicycle. An autonomous bicycle is just not about maintaining the balance but also controlling where the bicycle is heading. Following paths has been accomplished with bicycles and motorcycles in simulation for a while. Car-like vehicles have followed paths in the real world but few bicycles or motorcycles have done so. The goal of this work is to follow a planned path using a physical bicycle without overcoming the dynamic limitations of the bicycle. Using an iterative design process, controllers for direction and position are developed and improved. Kinematic models are also compared in their ability to simulate the bicycle movement and how controllers in simulation translate to outdoors driving. The result shows that the bicycle can follow a turning path on a residential road without human interaction and that some simulation behaviours do not translate to the real world.

(3)

Acknowledgements

I would like to thank my supervisors for their guidance and for pushing me to improve and develop my work. A thanks to Henrik Falk for driving me and the bicycle platform down to Gothenburg. From Chalmers University of Technology I would like to thank Maxime Feingesicht, Jonas Sj¨oberg and Lucas Wild for their input and help thesting the platform. Additionally a big thanks to the people at Systems, Control and Mechatronics at Chalmers for making me feel welcome during my stay.

Thank you to Linus Syr´en for the walks in the forests and helping me clear my head.

Finally, I would like to thank Vinnova for founding the research project, which this thesis is a part of.

(4)

Table of Contents

1 Introduction 1 1.1 Problem Formulation . . . 1 2 Background 3 2.1 Control theory . . . 3 2.2 Path planning . . . 3 2.3 Modelling . . . 4 2.4 Related work . . . 5

2.4.1 RRT based path planning approaches . . . 6

2.4.2 PID control approaches . . . 6

2.4.3 Fuzzy and fuzzy PID control approaches . . . 6

2.4.4 Model based tracking . . . 7

3 Method 8 3.1 Evaluation method . . . 8

4 Hardware 9 5 Implementation 10 5.1 Bicycle controller structure . . . 10

5.2 PID structure . . . 11

5.3 Path tracking . . . 11

5.4 Kinematic model . . . 12

5.4.1 Kinematic model 1 . . . 12

5.4.2 Kinematic model 2 . . . 13

5.5 Path position evaluation . . . 13

5.6 Lateral error . . . 14

6 Experimental Setup 15 6.1 Positional hardware . . . 15

6.2 Yaw drift . . . 16

6.3 Heading controller on roller . . . 16

6.4 Heading controller outside . . . 16

6.5 Lateral controller . . . 17

6.6 10km/h balancing . . . 17

6.7 Lateral controller at 10km/h . . . 17

6.8 Tuned lateral path controller . . . 17

6.9 Evaluation of lateral path controller using collected data . . . 18

6.10 Lateral and heading path controller . . . 18

6.11 Lateral and heading path controller turning . . . 18

7 Results and discussion 19 7.1 Positional hardware . . . 19 7.2 Yaw drift . . . 20 7.3 Heading on roller . . . 21 7.4 45 degree turn . . . 22 7.5 Lateral control 14km/h . . . 24 7.6 10km/h balancing . . . 24 7.7 Lateral control 10km/h . . . 26

7.8 Tuning lateral path controller . . . 28

7.9 Evaluation of collected data . . . 30

7.10 Lateral + heading path controller . . . 32

(5)

8 Conclusion 38 8.1 Future work . . . 38

(6)

1

Introduction

A bicycle is a stable system given adequate velocity, however, the minimum velocity for self-stability depends on the physical parameters of the bicycle and varies between models. ˚Astr¨om et al. [1] presented a bicycle that is self-stabilising between 21 and 36km/h while the presented bicycle of Schwab et al. [2] is self-stable in the region 15.5 to 21.8km/h. Normally the human operator balances the bicycle by transferring its weight and doing manipulations of the steering angle. The way humans control a bicycle is discussed in the work of Doyle [3]. A human mainly uses the steering angle for balance, which is also noted in the work of Moore et al. [4]. Doyle also mentions that controlling a bicycle using the bodyweight is also possible but only because of the front fork design of modern bicycles having a self-stabilising effect. The self-balancing effect can be used by active weight transfer methods with a pendulum or gyroscope with rotating mass.

As part of a project between M¨alardalen University, AstaZero AB, Volvo Cars Corporation, M¨alardalens University, Cycle Europe AB and Chalmers University, financed by Vinnova [5]. The instrumented bicycle, named Autobike [6], that is utilised in this master thesis was developed at M¨alardalen University. The goal of the project is to develop a bicycle that should be able to move realistically and represent a human cyclist when driving using a test dummy. Radar testing today with the goal to avoid bicycles in Euro NCAP is done with a dummy sitting on a moving sledge which is pulled on a rail [7] and do not represent how a human bicyclist would move. Autobike already has balancing capability at a fixed velocity of 14km/h and can be steered from a remote control by manipulating the target lean angle up to ±20 degrees. Autobike controls the steering angle directly using a motor instead of a gyro or pendulum due to the large physical footprints those units take up, which can disturb the visual side representation of the bicycle on radar images. An autonomous bicycle is not just about maintaining the balance but also controlling where the bicycle is heading. The difference between a balancing bicycle and a robotic system e.g. differential drive is that the bicycle can not stop or suddenly change direction without losing its balance and crash. For a bicycle to be autonomous it has to be able to follow a created path but also plan the route which the bicycle is taking using a path planner. A path planner has to adhere to the limitation associated with the bicycle and create paths that can be followed at adequate velocity without the bicycle falling.

In a simulation environment the bicycle dynamic properties can be simulated using a dynamic model like the Whipple model [8] or it can be modelled as a point [9]. For a bicycle behaviour in regards to positioning in a simulation environment, a kinematic model can be used to predict the movement in space of the bicycle. A bicycle kinematic model have can also be used for a car like robots or more complex models [10]

The rest of the paper is structured in the following way, with the problem formulation and research questions at the end of the current section. Section 2 gives a background into path tracking and path planning with a focus on vehicles with kinematic or dynamic limitation such as bicycles. Background also cover kinematics models for use with bicycles. The method used is explained in section 3 and also cover the evaluation method. The hardware of the bicycle with the attached sensors and compute-units are explained in section 4. The implementation is covered in section 5, experimental setups in section 6 and the results and discussion the experiments are combined in section 7. The thesis is wrapped up with the conclusions in section 8.

1.1

Problem Formulation

A bicycle has a limited ability to change direction and have to maintain balance while driving and turning so as not to crash. In this master thesis, a path tracking controller and path planner will be designed in simulation and implemented on the Autobike.

The bicycle uses a Proportional-Integral-Derivative (PID) controller for balance, by sensing the lean angle and actuation on the steering angle. However, there is a steady-state error between the reference and actual lean angle where its effect on path tracking will be investigated. Performance of controllers and planners will be evaluated first in simulation and through experiments on an instrumented bicycle using deviation error and under/overshoot of the path.

As the dynamics of the bicycle changes with acceleration, constant target velocity will be considered and the following research questions are formulated:

(7)

• How to create a path tracker which considers the dynamic and kinematic constraints of a bicycle balanced using handlebar actuation?

• How to create an adaptive global path planner with respect to the bicycle dynamic and kinematic constraints?

• How do the lean-inaccuracies affect navigation and expectations when turning, can it be compensated for?

• How do two common kinematic models of a bicycle compare to each other when used as part of a simulation environment to generate feasible control parameters for an instrumented bicycle.

(8)

2

Background

The background is structured with control theory first, the theory of PID controller and fuzzy. The next section contains path planning with a focus on RRT and comparing with other common methods. Then modelling of bicycle dynamics and kinematics is explore connected. The last section is the related works of how RRT has been used with vehicles to plan paths focused on turn limited vehicles and unstable vehicles and methods for those vehicles. Related works also include path tracking using PID, fuzzy and models using both bicycles, motorcycles and car-like vehicles.

2.1

Control theory

There exist many different control algorithms for controlling both stable and unstable systems. For example, a PID controller is used to directly minimise an error between a reference and the actual value. A PID is built out of three parts added together, the current error, the integral of the error and the error derived [11] and a classic PID controller [12] can be seen in equation 1.

u = KPe(t) + KI Z t 0 e(t) dτ + KD d e(t) dt (1)

Every part has a separate gain to balance the individual functions. A PID controller can be just a proportional P part, proportional-derivative PD, proportional-integrate PI or all three as a PID [13].

Another control algorithm is a fuzzy controller which through a process involving fuzzy logic and rules can control a system. The input to the fuzzy controller runs through a fuzzifier which assigns the input value, called a crisp value, into membership of a fuzzy set. For each input such as temperature, the input is assigned to a member of a fuzzy set such as ”hot”, ”mild”, ”cold” etc. The membership can look like 0.6 of ”warm” and 0.4 of ”cold” and those membership are compared using rules based on knowledge for the system to give a rule output for multiple inputs. A rule can be set as e.g. ”IF temperature IS hot AND water-flow IS low THEN water-valve IS open” which would give a fuzzy membership output of a fuzzy set of how much the water-valve should be ”open”. Multiple rules using the inputs to give a rule output for every rule which are combined using defuzzification to give a final crisp output number that can be used to control the valve to a specific position to control the system [14] [15].

2.2

Path planning

Path planning is essential for many mobile robots and is a popular research topic. In the review by Milanes et al. [16] the authors explore the current state of path planners using Rapidly-exploring Random Tree (RRT), state lattice, interpolating curve planners etc. The authors compiled the advantages and disadvantages of the methods and the use of the methods by research groups around the world. Paden et al. [17] presents a similar survey but broadening the scope from just path planners to include path trackers and do a deeper dive into some of the methods.

The survey made by Noreen et al. [18] dives deep into RRT and RRT* planners. They also explore related works adaptations of RRT and RRT* with different improvements that make RRT based planner better in certain use cases. Rapidly-exploring Random Tree (RRT) is a path planning method that is using random samples out from the tree in the search space like branches on a tree [19]. There are a lot of variants using the theory behind RRT and some of them have an idea of how to improve one or multiple aspects of RRT such as collision after a path is found with or smoothing [20]. Most of the variants are based around RRT or RRT*, where the difference is that RRT* rewire edge tree nodes to make a more optimal path [21]. A visual representation of the tree looking structure of RRT path planning can be seen in Figure 1.

(9)

Figure 1: Visual representation of RRT exploration using random trees out in the space from the start green start point to the red finishing point. The red path is the found path from start to finish and further exploring could yield a shorter path to the goal.

One way to improve the convergence speed of RRT* is the proposed version informed RRT* by Gammell et al. [22]. It executes like RRT* until a solution is found but then changes to sample in a subset and focuses to more exploitation. Informed RRT* does not always produce a better path but it can shorten the total planning time.

Another way to improve RRT* base can be like Karaman et al. [23] where they in an online environment extend the RRT* base by not only doing an initial path plan. Their extension updates the path by exploring better paths further along from where the robot is located. They do tests in simulation as well as experimental tests outside using a self-driving forklift.

Cubic splines [24] and B-Splines [25] are two methods of interpolation with the ability to fit continuous curves to existing curves and can have continuous derivatives. It can be useful when using a path planner to create continuous paths that can create change in direction without any jerk in the motion while driving [26].

2.3

Modelling

A kinematic model is used to calculate the lateral motion of a vehicle based on the vehicles geo-metric properties and control actions, such as steering angle. One such kinematic model designed for a bicycle is explained by Rajamani [27] and is used in the works of Polack et al. [10] and Kong et al. [28]. This kinematic model shown in equation 2 calculate β which is the angle at the mass centre of the bicycle velocity. The variable ∆ is the steering angle of the bicycle at the road plane, a is the distance from the rear wheel to the Centre of Gravity (CoG) and b is the distance between the rear and front wheel both at the point of contact with the road. A visual representation of variables used in this thesis and their representation on the bicycle shown in Figure 2.

β = arctan (a

btan (∆)) (2)

The lateral motion and heading is shown in equation 3 where v is the forward velocity of the bicycle, θ is the heading of the bicycle and ψ is the inertial heading, with a visual representation seen in Figure 2.     ˙ x ˙ y θ ˙ ψ     =     v cos θ v sin θ ψ + β v asin β     (3)

In the works of Meijaard et al. [29] the authors note the difference in using a steering angle at the handlebar δ which they used, to a steering angle at the road plane ∆ which was done in the works

(10)

b a h Y X β ψ θ 𝛿 ε ϕ CoG ∆

Figure 2: Visualisation of the bicycle and the variables. Direction of the arrow for angles is in positive direction

by Herfkens [30] and are shown in equation 4 with  being the caster angle of the front fork.

∆ = δ cos() (4)

Another kinematic model build to fit a motorcycle is explained by Cossalter [31] chapter 1.10 and is shown in equation 5 where the curvature C of a circle with radius R is calculated. The model uses the roll angle φ and caster angle  otherwise known as the angle of the front fork in the travelling direction of the bicycle and the coordinate system is placed at the back wheel instead of below CoG. C = 1 R ∼ = cos  b cos φtan δ (5)

The Autobike platform is built on the work of Andersson et al. [32] and uses a point mass dynamic model to simulate the bicycles balance behaviour. Point mass model is a basic bicycle model which places all the mass of the bicycle in one point which is the centre of gravity. The model assumes that there is no wheel inertia and also that the caster angle and trail distance is zero. The point mass model transfer function the authors used is shown in figure 6.

Gϕδ(s) ≈ av bh s +v a s2g h (6)

The authors used the steering motor step response to approximate a second degree transfer function with time delay. Then the motor response can be used in a simulation environment with the transfer function shown in equation 7.

P (s) = e−d·s ω 2 n s2+ 2ζω ns + ωn2 (7)

Where d is the time delay in seconds, ωn is the natural frequency and ζ is the damping ratio of the system.

2.4

Related work

The full dynamic system of a bicycle is computationally heavy when creating feasible paths, there-fore authors Polack et al. [10] compared a kinematic model to a 9-degree of freedom dynamic model to see if the kinematic model correspond when path planning. During testing in simulation, some

(11)

slip did occur at higher velocities in their dynamic model compared to their kinematic model. They looked into the safe limit for their kinematic model and concluded that the limit is 0.5µg where µ is the tire friction to the road.

Path planners that seek continuity to create a smooth path are limited since they cannot be built of straight lines but need some way of connecting the whole path. In the work of Katrakazas et al. [33] they explore different types of implementations of state lattice and compare it to RRT. Both explore the state space using trees vs lattice but lattice created continuous and smooth paths. The updated RRT* star can guarantee optimality but for smooth paths, some smoothing is needed to be done e.g. using B-splines. The authors explore the different ways lattices have built and different approaches that have been made to reach varied problems.

2.4.1 RRT based path planning approaches

There are ways to make sure that dynamic or kinematic models are incorporated or at least the limitation of the robot. The authors Pepy et al. [34] incorporate the model into the planner and compare the path created using a kinematic model and a dynamic model of a bicycle. A way to control the curvature is by building splines into the planner similarly to State lattice, but it requires to add steps into the planner which is what has been done by Lee and Shim [35], Yang et al. [36] and Yang [37].

A simpler way of smoothing paths is to not incorporate the splines into the planner but as a post-processing technique as done in varying ways by Sudhakara et al. [38], Shan et al. [39], Elbanhawi et al. [40] and Jung and Tsiotras [41].

2.4.2 PID control approaches

To avoid the vehicle drifting of the planned or pre-created path, some sort of path or trajectory follower have to work to get the bicycle back on the path. One way to solve the tracking problem is to use a PID controller. In the works by Savoye [42] a regular tuned PID was used to simulate trajectory following on a bicycle. The steering angle was manipulated with the PID to change direction while the balance of the bicycle is done with a Linear Quadratic Regulator(LQR) by controlling the angular velocity of the handlebar.

In the work of Farag and Saleh [43] a car followed a pre-determined continuous track in a simulation environment where the steering angle is controlled using a PID based on cross-track-error, which is the error of the vehicle to the centre of the track. Using three different methods the tuning of the PID controller was iterated several times. The gains of the PID controller had different effects, P was vital to follow the track but changing it had no large change in result, D was the most important tuning parameter as it had the most effect on how well the vehicle took the path but the integration parameter did not have that much of an effect and sometimes worsened the result. In the end, the vehicle was able to take the path at 88km/h using a controller correcting for lateral error.

In the article by Dao and Chen [44] the angular and positional error is calculated separately and use a P gain on the angular error and PI on the positional error and then added the two parts together. This gives a reference roll angle which indirectly affects the direction of the bicycle when the balance controller tries to reach that reference roll angle. Karaman et al. [23] also use a path tracking controller with a heading error and lateral error added together and balanced by gains. Both the heading error and lateral error use a P gain separately but the lateral error is saturated by arctan .

PID is not the only local path-following method available, as Pacheco and Luo [45] test Model Predictive Control (MPC) and PID controllers side by side and compare the performance using a differential drive robot. MPC did give perform better when it can to positioning error but PID is simpler and have faster computation time.

2.4.3 Fuzzy and fuzzy PID control approaches

Fuzzy is another method that can be used, either alone or together with PID, as in the work of Xianbo Xiang et al. [46] where a fuzzy PID controller is used to follow a 3D path. The simulation result is compared to two regular PID controllers and two backstepping-based controllers.

(12)

There are bicycle path tracking done in a simulation that are using fuzzy controllers. For example in the work of Dao and Chen [47] a Fuzzy Inference System is used to minimise the distance and tangent angle to the closest point on the path and the bicycle roll angle is manipulated when turning for following a path. The controller is modified for taking the yaw angle into account to improve the path tracking steady-state error.

In another paper written by Dao and Chen [48] the bicycle use a preview point a short distance in front of it and calculate the errors at the preview point using an error estimator. A regular fuzzy controller is used to calculate a reference roll angle to follow the path and is tested in simulation. There have been few actual bicycles with path planning and path following which have been tested outside of the simulation. One of them is by Zhao et al. [49] where PD controllers are used for both distance deviation and yaw angle deviation for path tracking. The two PD controllers are added together with weights to manipulate the roll angle setpoint of the bicycle.

2.4.4 Model based tracking

There are other ways to track a path that is not PID and fuzzy. In Sniders works [50] multiple geometric, kinematic and dynamic controllers was tested using test courses in the simulation en-vironment CarSim. The performance of the different controllers was depending on the scenario. For example, the geometric path followers working better at the slower speed, down to 5m/s, the preview controller, based on the dynamic model is also of interest.

In the works of Yi et al. [51] a path following based on the dynamic bicycle model was tested in simulation and it also planned small trajectories between each target position.

(13)

3

Method

The iterative engineering design process is used as a methodology in this thesis, which is described in details in the work by Tayal [52]. First, a literature study is performed to investigate related work path planning and path tracking for bicycles. Path planner and a set of path tracker controller is to be developed first in simulation and then experimentally verified on Autobike. In a simulation environment, the path tracking controllers are tested using test cases that can be repeated on the physical bicycle and include, but not limited to, turning radius, changing direction, following a straight line and adding disturbances. By reducing the turn radius and increasing disturbances the limitations of the path tracking controllers are evaluated. In the simulation, different controllers are evaluated using the Root Mean Square Error (RMSE) and the standard deviation of the bicycle when following a path. The same path that is used in the simulation is also tested on the bicycle to verify and compare with simulation. Path planning is to be evaluated by keeping within limitations of the path tracker controllers capabilities and path calculation speed.

The test grounds at AstaZero [53] have a base station for increased accuracy when using Global Positioning System (GPS) [54] which would provide better raw GPS data for the tracking controller if it is available to use during the master thesis. The bicycle velocity and steering angle are received from the ODrive motor controller using the internal hall sensors for velocity and encoder for steering position which is used for dead reckoning.

Path planning and tracking are developed in Mathworks Matlab [55] and simulated in Math-works Simulink [56]. Path tracking implementation on the bicycle is implemented on the bicycle computation platform roboRIO [57] programmed using the development environment Labview [58] and the data is evaluated using Matlab.

3.1

Evaluation method

To evaluate the capabilities of different controllers, test paths are used. RMSE and standard deviation are used to give a performance metric for each controller that is evaluated. Four test paths are used and include a 100m straight, 45-degree turn with 10m radius and a 180-degree turn with 15m radius which can be seen in Figure 3. The fourth and last path is RRT* generated path using Matlab Navigation Toolbox [59] that is configured using only dubins vehicle state-space model [60] with a minimum turning radius of 10m in the testcase due to time limitations. The RRT* planner is tasked to avoid a wall at x = 40m and then the RRT* created path is smoothed using cubic interpolation from the Matlab Automated Driving Toolbox [61] using an interpolation distance of 0.03m between samples. The four test cases were all selected to test and challenge the bicycle path following ability with both simple and more complex cases. From these four cases it is also possible to to expand to more complex test cases and increase the difficulty by reducing turning radius. As a test area, a residential road is used for most of the outdoors testing and it

0 20 40 60 X (m) -30 -25 -20 -15 -10 -5 0 5 Y (m) Test case 1 0 20 40 60 80 100 X (m) -5 0 5 Y (m) Test case 2 0 5 10 15 20 25 X (m) -5 0 5 10 15 20 25 30 35 Y (m) Test case 3 0 20 40 60 80 X (m) -10 0 10 20 30 40 50 60 70 Y (m) Test case 4

Figure 3: Test cases that are evaluated in simulation with the goal of run outside on Autobike

(14)

4

Hardware

Autobike is based on a Monark Sture [62] electric bicycle with a mid mounted Shimano STePS e5000 motor [63] for propulsion. Steering angle is manipulated using Model Motors AXi 5345/16 HD GOLD LINE [64] Brush-Less DC motor (BLDC). The bicycle core processing unit is a National Instrument roboRIO [57] and is accompanied with a open source Odrive robotics Odrive V3.6 56V [65] two channel servo motor controller and control the motor velocity for propulsion and steering angle position. Since the ODrive is controlling the velocity on the bicycle using HALL [66] sensors on the propulsion motor, the ODrive velocity measurement is an accurate way of tracking the velocity. But the bicycle rear wheel will freewheel to the motor when the velocity is higher than the motor speed, so the measurements are flawed when driving downhill and the motor is not accelerating the bicycle. The bicycle is equipped with a VectorNav Technologies VN-200 [67] Attitude and Heading Reference System (AHRS) with Global Navigation Satellite System (GNSS) using GPS which deliver data at 100Hz. The VN-200 AHRS is used for both roll angle, yaw angle measurements from the Inertial Measurement Unit (IMU), positioning using GPS of the bicycle and uses a Extended Kalman Filter (EKF) internally to fuse GPS data with IMU data for more stable and accurate output. All electronic hardware except for the VN-200 and propulsion motor is placed inside of the bicycle basket mounted in the front on the bicycle frame and is shown in Figure 4. Positioning with a Decawave DWM1001 [68] using Ultra-Wideband Radio (UWB) with locally placed DWM1001 tags is also implemented on the bicycle and can be used instead of GPS when testing indoors or in areas with a poor GPS signal. To operate functionality of the bicycle while running, a remote controller using a nRF24L01 [69] transceiver at 2.4GHz is used. The remote control can transmit target velocity, running mode, bicycle shutoff and target lean angle offset and receive information about current velocity, lean angle and target lean angle. The change of travelling direction on Autobike depend on the lean angle which the balancing controller target a lean setpoint, manipulated by an operator or a position or path tracking controller.

Battery GPS antenna

AHRS Electronics

Propulsion motor

Figure 4: Instrumental bicycle used from project Autobike. Electronics contain main computer, motor controller, steering motor and radio receiver.

(15)

5

Implementation

In this section, details of the implementation are discussed. Starting off with the controller struc-ture on the bicycle and how the bicycle is strucstruc-tured in the simulation environment. Then the PID controller structure and how the implementation is different between simulation and the physical bicycle. Thereafter, the control structure for path tracking is explained, how the lateral deviation error and heading deviation error is calculated and used with controllers. The kinematic models are presented in detail and how they are adapted for the use on the bicycle. Next, the process of path identification and how to find the closest place on the path from the bicycle is found. Lastly the function for calculating lateral error that is used in the path tracker. The parameter explanation and physical representation for Autobike are shown in Table 1 and are used in the implementations.

h Distance of the CoG from the ground 0.562m a Distance of the CoG from the rear wheel center 0.505m b Distance of the front to the back wheel centers 1.115m h Height of the CoG from the ground 0.562m

m Mass of the bicycle 25Kg

 Caster angle of the front fork 24◦

g Gravity constant 9.82m/s2

θ Heading of the bicycle

-δ Steering angle

-∆ Steering angle in the road plane -β Angle at the mass centre of the bicycle velocity -ψ Inertial heading of the bicycle

-φ Bicycle roll angle

-Table 1: Explanation of the bicycle physical parameters and their representation.

5.1

Bicycle controller structure

In figure 5 the structure of the bicycle controllers can be found. The VN-200 AHRS deliver angle and position data at a 100Hz frequency which is used by the balance controller which runs with a 100Hz frequency and the path controller running at 10Hz. There are disturbances on position and angle data from the VN-200 because wires pick up disturbances from power and propulsion motor phase cables during communication and result in spiking measurements. The balance controller uses a PID controller and the input and output use a rate limiter with a 75◦/s limit to reduce the effect on the output steering angle from disturbances and a saturation limit of 65◦/s to limit the output signal. The path tracking controller can remove the disturbances when downsampling the 100Hz data to 10Hz using a median filter. The path tracker takes both feedback and reference values for position and heading to calculate errors internally. How the reference path position and heading value is selected, it is explained in section 5.5 and the path tracker itself is explained in section 5.3. In the simulation environment, bicycle behaviour is simulated using a structure

Path Tracker Balance Controller Motor Controller VN-200 AHRS Physical Bicycle + - ϕ ϕ 𝛿 + -Reference Path Motor Encoder 𝛿 X, Y, θ X , Y , θr r r r r

(16)

of models and transfer functions seen in Figure 6. The steering motor and motor controller is not modelled individually, instead, a transfer function of the step motor step response is used to simulate the steering response of an input. The transfer function in equation 7 is used with a natural frequency ωn = 33.9, damping factor ζ = 0.6 and a delay in time of d = 0.015. The parameters are obtained by using step response matching of the handle bar step response, but parameters that is used on this bicycle platform is the same as the older bicycle platform in [32]. Point mass model is used as a dynamic model and the general transfer function for the bicycle can

Path Tracker Balance Controller Steering Transfer Function Kinematic Model Bicycle Dynamic Model + - ϕ ϕ 𝛿 Reference Path X, Y, θ X , Y , θr r r r r 𝛿

Figure 6: The structure of the bicycle controllers and feedback when the bicycle is simulated.

be seen in equation 6 using the parameters from Table 1. A kinematic model is used to calculate the lateral movement the bicycle in the simulation environment to simulate how the bicycle moves and is explained in section 5.4.

5.2

PID structure

The structure used for PID controllers is an ideal/standard form as the controller in Labview uses that form but Matlab and Labview still have differences in their structure. The time-discrete Matlab PID controller equation is not disclosed by Mathworks, the time-discrete transfer function is and is shown in figure 8 [70] with the sampling time Ts. The Matlab PID uses the error as input and is configured to use a trapezoidal integration method and no derivative filtration.

C(z) = Kp(1 + Ki Ts 2 z + 1 z − 1 + Kd 1 Ts z − 1 z ) (8)

Labview PID can be seen in equation 9 and have some differences to the Matlab structure. Labview use both a setpoint (SP) and a current value called Process variable (PV) to calculate the error e using e(k) = SP − P V internally, but the derivative term uses only the process variable and not the calculated error [71]. One other difference is that the Labview PID derivative gain Td and integration gain Ti use time in minutes. To convert from the Matlab derivative gain Kd and integration gain Ki to the Labview gains, equation 10 and 11 is used for integration gain and derivative gain respectively. Saturation limit is also built into the function and it use a integral sum correction for upper and lower output signal limitation so that the integral term is not growing outside of the limit.

u(k) = Kp e(k) + 1 Ti k X i=1  e(i) + e(i − 1) 2  Ts+ (Td) −1 Ts (P V (k) − P V (k − 1)) ! (9) Ti= 60 Ki (10) Td= Kd 60 (11)

5.3

Path tracking

By manipulating the roll angle setpoint Autobike can change direction and the degree of turning is proportional with the roll angle set point. Autobike path following controller is executing at 10Hz and the 100Hz AHRS data is downsampled using a median filter to remove spiking data created by

(17)

disturbances which are picked up during communication through the bicycle frame. Two available metrics with errors that a controller can minimise is the lateral deviation and the angular deviation of the path. As explored in section 2.4.2, path tracking with PID controller often use one controller for heading control and one for lateral control. The path tracker has the option to use a lateral and a heading controller ether separate or together with the structure seen in Figure 7 and each controllers use a output saturation of 10◦/s.

Lateral Controller + Lateral Error Heading Controller + -θr X , Y , θr r r X, Y, θ Current Path θ Reference Path + ϕr el eθ Output

Figure 7: The structure in the path tracker which include two controllers and a lateral error function. Green block is input and red is output from the path tracker.

The two controllers are both PID controllers but calculate the error beforehand, so the Labview PID implementation explained in section 5.2 only use the error as PV and the setpoint is 0 to minimise the error.

5.4

Kinematic model

Two kinematic models are used in this thesis and are referred to as model 1 and model 2. Model 1 is based on the work of Cossalter and equation 5 and model 2 is based on the work of Rajamani with equation 2 and 3. Kinematic model 1 was proposed during project Autobike and model 2 is more commonly used for bicycles and for simplified cars like vehicles.

5.4.1 Kinematic model 1

The kinematic model by Cossalter in equation 5 only calculate the turning curvature of the turn. To calculate a lateral movement of the bicycle, equation 12 is used.

    ˙ x ˙ y ˙ θ ˙ Θ     =     v cos θ v sin θ ˙ Θ 2 vR1     (12)

It uses the relation S = RΘ which is visualised in Figure 8, where S is the distance travelled at a velocity v during a time-period. For the calculated ˙Θ, the velocity v is used directly. We assume that ˙Θ will not exceed ±π2 in a single time step, and therefor ˙θ = arctan (1−cos( ˙Θ)

sin ˙Θ ) = arctan (tanΘ2˙) = Θ2˙. Also when the curvature C = 0 which happens when the steering angle δ = 0, the angle Θ = 0 and will lead to the equation ˙θ = arctan (1−cos( ˙Θ)

sin ˙Θ ) being undefined because of arctan (00) division. Since this is when the bicycle is going in a straight line and would lead to a travel direction of ˙x = v , the simplification used in equation 12 include the special case when d is approximated using v .

(18)

Θ

R

S

θ

X

Y

d

Figure 8: Visual relation of θ and the S = RΘ relation. R is the radius of the turn and S travel distance along the curve

5.4.2 Kinematic model 2

Kinematic model 2 in equation 3 and 2 are built for a bicycle model on the road plane, so the steering angle is measured at the road plane. The steering angle for Autobike is instead measured at the handle bar and not the road plane. Using the relation in equation 4, the steering angle δ in equation 2 is replaced with δ cos  to form a replacement equation 13.

β = arctan (a

btan (δ cos )) (13)

5.5

Path position evaluation

Even though the bicycle position is measured when driving, it is not known which point on the planned path to compare against. Regardless of which direction the path is headed, it should always be possible to find what point on the path to use as the reference. To identify the current path position, a line orthogonal to the heading direction can be used as a separator to decide if the bicycle is behind or forward of the line and that point on the path curve. The normal of the line is created in equation 14 by making a vector of the path heading since it is orthogonal to the line.

~

n = [cos(v), sin(v)] (14)

To identify which side of the line the bicycle is currently positioned the inner product is used, seen in equation 15. The result d is the distance to the bicycle in the direction of the normal vector from the position of the path that is currently tested against but is effectively the distance of the bicycle to the line and is visualised in Figure 9.

d = h[Xbike− Xpath, Ybike− Ypath], ~ni (15) In the start of each time-step for the lateral controller, a new position on the path has to be found closest to the new bicycle position to calculate the lateral and heading error. Using a iterative process shown in figure 10, path identification step forward through the planned path until the bicycle position is found.

From one loop iteration to another the bicycle change from one position to another but unknown how far the bicycle has moved on the reference path and so an iterative process shown in Figure 10 is used to find how far using the equations just described.

(19)

θr

n

d-d+ d

Figure 9: Visual representation of the unit vector ~n, reference heading θr at the current compared path point for path identification where ~n k θr. The sign of the distance d to the bicycle in relation to the normal vector. Choose next path position Use bicycle last path position Calculate distance to line Save path position Save path position Bicycle in front of line? Output saved path position yes no

Figure 10: Flowchart of the iterative process of choosing a reference position on the path.

5.6

Lateral error

To give a good representation of the distance the bicycle deviates from the path a error function is used. Using the same idea as in section 5.5 but with the difference that the normal vector now will be orthogonal to the heading direction and parallel to the line described there. It means that using the new normal vector in equation 16, equation 15 will now give the distance out one the line from the reference path position.

~

n = [cos(v −π

2), sin(v − π

(20)

6

Experimental Setup

To evaluate and develop the bicycle towards the goal, several experimental setups are used to test the bicycle implementations shown in section 5. In this section, the experimental setups are explained, starting with a description of how positional hardware is evaluated by logging sampled signals. Then a description of how to evaluate where and why a yaw angle is drifting. Explanation of a controller on a bicycle roller is tested are next which is followed by another heading controller but the testing is done outside. The following test described is a controller using the lateral error on a residential road shown in Figure 11. This residential road is also used for all subsequent tests and all tracking controllers are tested first on the straight driving a path south to north. Then a description of how a balance controller using a lower 10km/h is tested. It is followed by a lateral controller test using the slower 10km/h velocity and balance controller which is also used for all subsequent test. Next, the description of how a lateral controller is tuned and tested which is followed by a description of how outside behaviour on the bicycles is tested and evaluated back in the simulation environment. Then the explanation on how a two combined lateral and heading controllers is tuned and tested using two kinematic models. Finally, one of the last tested controllers is tested taking a turn on the residential road.

-60 -40 -20 0 20 40 60 X(m) -60 -40 -20 0 20 40 60 Y (m) N S

Figure 11: Residential road available to use. Boundaries of the road are collected the bicycle GPS driving at the edge of the road.

6.1

Positional hardware

All available sensors that can be used to give a position estimate for Autobike are tested when driving around Chalmers University campus with the path taken seen in Figure 12. The test is performed using a velocity of 3-7km/h with the operator holding the bicycle while sampling of GPS position, current velocity, yaw, roll and steering angle is done on the bicycle. Afterwards, the sampled signals are used to recalculate the path in Matlab by integrating the yaw angle, integrating a heading derived from the GPS position and using kinematic models 1 and 2 which are explained in section 5.4. The GPS positional data from the VN-200 is in focus to understand how it behaves in an urban environment with tall buildings and if the position is usable as it is

(21)

received from the AHRS without a jump in position. The recreated path from integrating models and sensors are compared with the VN-200 AHRS GPS position to evaluate which one or ones are close to recreating the original path driven around the facility. The recreated path likeness to the originally driven path can also be used to evaluate which heading is most stable and practical to use as a heading directly. Roll angle from the VN-200 receive disturbances picked up in the wires for communication which result in spiking measurements to the balance controller. A rate limiter used in the balance controller to reduce the effect of spiking measurements and such rate limiter is also used for GPS position and yaw angle.

Figure 12: The path walked with the bicycle around Chalmers University campus walking clockwise with arrows indicating walking direction with starting and finishing point at the green marker. The walking pathway on the right hand side has been widened since the satellite image was taken.

6.2

Yaw drift

During initial testing of the heading controller on a bicycle roller, drift in the yaw angle measure-ments was discovered. The drift was also noticeable when the bicycle was held in a steady upright position. To investigate further, yaw angle measurement is collected while driving on a bicycle roller and compared with the outdoor test of yaw angle in section 6.1.

6.3

Heading controller on roller

To test that a controller with only the bicycle heading angle is functioning on the bicycle, a change of heading with 1.5 degrees during 500ms will move the bicycle over from one side of the roller to the other and then again the opposite direction. The velocity is set to 14km/h and the navigation controller use a sample rate at 10Hz with proportional gain −0.4 of heading and derivative gain of 0.04. The controller is the first stable controller found in simulation and is used as a baseline for further evaluations.

6.4

Heading controller outside

As the bicycle roller is too small to verify that a heading controller can follow a turning path without hitting the side of the roller, the bicycle heading controller have to be tested in an outdoor environment with few obstacles. The path is based on test case 1 but with a radius of 20m to fit the open area where the bicycle turned around in the top left from Figure 12 in section 6.1. The corner driven at is an off-camber turn which means the ground is slightly slanted away from

(22)

the turning direction. The 45-degree path used is based on time, which means that it will change the target heading based on the target curve just based on how long time the bicycle has been driving. If the bicycle would go faster or slower it will take the turn with a different radius than the planned 20m but the heading will move down to 45 degrees as planned. The setup uses a proportional heading gain of −0.2, a sample rate of 10Hz and target velocity of 14km/h.

6.5

Lateral controller

When controlling the bicycle using the lateral error of the path, the time based reference path used in section 6.4 can quickly diverge from the actual bicycle position. For lateral control the path identification explained in section 5.5 is used to find the position on the path the bicycle should compare against when calculating the error. Lateral error function explained in section 5.6 is also used and measures the side error to the path in meters. The test is set up to verify that the lateral controller correctly setup in terms of direction of input and output as well as the path identification and lateral error. The bicycle is tested using a manually tuned lateral controller with proportional gain of −0.2 running at 10Hz with the bicycle running a target velocity at 14km/h. The path used to verify the lateral control is a straight line in the middle of the residential road shown in Figure 11. The straight path is created to be run from south to north with a angle in the direction of the road and during the test, the operator give the bicycle a short, light push to evaluate how the platform recovers and gets back to the path.

6.6

10km/h balancing

For easier and safer operation of the bicycle and to create more margin on the usable driving area. The bicycle balance controller is tuned to lower velocity, from the original 14km/h down to 10km/h. To tune the balance controller, Mathworks proprietary transfer function based PID autotune [72] is used to find a set of balance controller gains for 10km/h. Another set of less aggressive balance controller gains was found by using a slight manual adjustment of the target response behaviour. Both new balancing controller parameters alongside the original parameters for balancing at 14km/h can be seen in Table 2.

14km/h 10km/h set 1 10km/h set 2 Gain: P 3.418 5.7844 4.8049 Gain: I 1.327 1.6066 1.1908 Gain: D 0.0646 0.0545 0.0566

Table 2: Matlab PID gains for balancing. Gain set 1 is the balance controller parameters chosen by Simulink autotune. Gain set 2 is the parameters chosen by the autotuner when the target response curve from set 1 is altered to be less aggressive.

6.7

Lateral controller at 10km/h

With a bicycle balancing tuned for a slower 10km/h driving, the lateral controller is restructured to make the controller gains positive with otherwise identical function. The lateral controller is now running using manually tuned proportional gain of 0.6 and a target velocity at 10km/h and is tested first in simulation before using the bicycle outside. The same straight path as in section 6.5 and the bicycle receives one quick push to the left from the operator to verify that the bicycle is correcting the lateral deviation from the path.

6.8

Tuned lateral path controller

For the first iteration of tuned controllers, only gains for the lateral controller are evaluated which bases its output on the lateral error as it was found in section 7.2 that combining heading with lateral requires work to calibrate the heading to the GPS direction. Based on an iterative process using trial and error in simulation, PID gains for the lateral controller is tuned to minimise RMSE of the cross-track error in simulation. In the simulation, the bicycle is started at a 1-degree lean

(23)

angle so that the bicycle is not on the perfect balance point. This will create a small lateral error for the lateral controller to compensate. The best resulting controller parameters from the simulation is evaluated outdoors on the bicycle driving in a straight line and the parameter is changed to a slower set of simulation parameters if the one first used are too aggressive and cause imbalance on the bicycle outside.

6.9

Evaluation of lateral path controller using collected data

Lateral error collected from the bicycle data is used as input to the lateral controller in simulation to evaluate if the simulated bicycle shows the same behaviour as the bicycle showed driving outdoors. The control parameters used in simulation agrees with those used outside and are given in Table 3. Additionally, a set using no derivative of the lateral to evaluate if the derivative terms effect on oscillations. The input lateral error is collected during the same time as Figure 25 and is used

Simulation set 1 Simulation set 2 Simulation set 3

Gain: Pl 2.8 1 2.8

Gain: Il 0.1 0.1 0.1

Gain: Dl 1 1 0

Table 3: Matlab PID gains lateral only to evaluate instabilities in simulation

in simulation with no position feedback to evaluate what in the output of the lateral controller destabilises the bicycle balance.

6.10

Lateral and heading path controller

As was found in section 7.9, derivative on the lateral error is not practical to use and produce oscillations. Instead, a heading controller is used together with the lateral controller because the yaw angle used for the heading is a smoother signal than the derived lateral error. The heading is a form of derivative as the heading error is the angle of the bicycle driving towards or away from the path. An increasing heading error is a bicycle turning away from the path or will overshoot the path and the bicycle have to be aligned in the direction of the path. To evaluate lateral and heading controllers, kinematic model 1 and 2 will both be used with a trial and error method of finding controller parameters using each of the models. The two models explained in section 5.4 and are both evaluated since it is not known which of the two kinematic models produce controller parameters which performs better on a bicycle outdoors. Initially, one set of controller parameters from each kinematic model are tested outside on the bicycle driving in a straight line. The controller parameters chosen to be run on the bicycle outside will initially be using a proportional lateral gain less or equal to 5. That is because a deviation of 2m with a proportional lateral gain of 5 will yield a target lean angle of 10 degrees which is on the limit of what Autobike has been tested on before falling in the project. If the bicycle is stable outside using the controller parameters then the controller parameters are changed to better and more aggressive parameters from the simulation results.

6.11

Lateral and heading path controller turning

To further evaluate a set of stable parameters for the lateral + heading controller, the path is changed from a straight path to a path which includes a turn. The residential road in Figure 11 is limited to what corners are available so none of the test cases can be used. Instead the path planned on the residential road is from north to south and turning west onto the side road with a 90-degree turn using a 15m radius at 10km/h

(24)

7

Results and discussion

This section cover the results of the test explained in section 6 as well as discussion about the results. First, the ability to recreated the driven path using sensors and models is compared. Then, the result and discussion of where and when drift in yaw angle occurs and if it stable over time. Next is the result of using a heading controller on a bicycle roller which is followed up by testing a heading controller outdoors. Then the result of using a lateral controller on a residential road. Thereafter the result of two different balance controllers using a 10km/h velocity followed by testing a lateral controller using a new controller at a slower velocity. Then the result of developing a tuned lateral controller and how two of the controllers in simulation perform when driven outdoors on the bicycle. The result from evaluating sampled lateral error from the last test using the controllers in simulation is next. After that, the result of developing two tuned combined lateral and heading controllers and evaluating two of them outdoors on the bicycle. Lastly, the result of the best one of the last two tested controllers when tested driving a curved path.

7.1

Positional hardware

-200 -100 0 100 200 300 X (m) -200 -100 0 100 200 300 Y (m)

Comparison of positioning methods GPS position

Yaw angle integrated position Kinematic model 1

Kinematic model 2 GPS derrived position

Figure 13: GPS path together with the position calculation using sensors, IMU yaw angle, derived heading from GPS and both kinematic models. Start position is 0:0. From the start point, there is a downhill and the bicycle freewheel and loses 100m all models first turn is earlier than the GPS reference position. GPS is unstable close to the start because of the houses blocking the signal

The start and end of the test were done driving straight between two buildings and the GPS position is not stable as seen in Figure 13. The position does not jump but rather drift back and forth between the buildings until the bicycle is in a more open area where the position stabilises. The road in the start between the houses is a slight downwards incline and the bicycle freewheeled over the motor velocity so the recorded velocity is slower than was actually driven which result in a shorter distance driven at the start for recreated paths. Recreating the path using a kinematic model is not possible and both models drift separate ways without being able to reassemble the original driven path. Recreating the driven path using the VN-200 IMU yaw angle is the closest to the GPS position and the driven path and the error built up is only noticeable halfway through the test. The yaw angle is closer to the original path than using a GPS derived heading and yaw angle requires no extra processing. For future tests, the yaw angle and GPS is used to as heading and position respectively and should not need to be fused with each other or other sensors as they

(25)

are already fused using an EKF inside the VN-200 beforehand. Fusing any other signals or model using a kalman filter would probably not provide any better positioning than using the already fused GPS signal in the tuned VN-200 unit. The future tracking controller is running at 10Hz so a median filter can be used instead of a rate limiter to remove spiking measurements and should remove disturbances that do exist in this test.

7.2

Yaw drift

Time (s)

Yaw angle 0 50 100 150 200 250 -10

Angle (degrees)

-5 0 5 10 15 20 25

Figure 14: Yaw drifts after startup. The reference angle is offset back to 0 in software and the bicycle is running on the roller during the time period

0 100 200 300 400 500 600 700 800 Time (s) -200 -100 0 100 200 Angle (degrees) Yaw angle 1. 2.

Figure 15: Yaw angle during the test in section 7.1 where the red marked are when the bicycle are driving horizontally in Figure 13. The difference between red line 1. and 2. is about 180 to 190 degrees from going in one direction and then coming back in the opposite direction.

Figure 14 shows the yaw angle drift after start-up and can take up to 3 minutes to stabilise indoors, sometimes it is stable already after start-up. Roll angle which comes from the same AHRS unit does not suffer the same behaviour. The behaviour is different from how the yaw angle behaved when the bicycle was moving outdoors in section 7.1 as can be seen in Figure 15 where

(26)

the yaw angle is 180 degrees different when the bicycle is coming back in the opposite direction without any noticeable drift. Internal filters between GPS unit and IMU unit inside the VN-200 calibrates the yaw angle when the bicycle is outside to stop drifting which will not work indoors where there is no GPS coverage. The VN-200 do not calibrate the absolute angle towards the travelling direction as restarting the bicycle will yield a different angle. To use a path tracking controller with both heading and lateral parts the yaw angle has to be calibrated towards the GPS heading. Otherwise, the bicycle might have unexpected behaviour when the heading controller uses a different zero on the heading angle from the lateral controller GPS direction. Also as the yaw angle differs between test runs it might lead to changing behaviour between tests. The need to power cycle the bicycle between tests was removed which allows running tests again if the yaw angle drifts or something else goes wrong. Additionally, the AHRS which sample the yaw angle does not need to recalibrate before each test when testing indoors.

7.3

Heading on roller

Time (s) Lean angle Steering setpoint Lean setpoint Path heading Yaw angle 0 2 4 6 8 -10 -8 -6 -4 -2 86 88 90 92 94 96 84 98 100 Angle (degr ees)

Figure 16: Heading controller with a change in the path direction. Oscillates more than just balance controller

When running the heading controller on the roller with the simulated -0.4 proportional gain and 0.04 derivative gain, the bicycle is unstable on the bicycle roller. Figure 16 shows the bicycle balance on the roller using the heading controller with a proportional gain of -0.4 with no derivative gain. Two times during the test the target heading is changed with 1.5 degrees but the resulting movement is too small to distinguish from bicycle side to side movement created from the heading controller. Without the heading controller, the bicycle has less side to side movement oscillation when driving on the roller which can be seen in Figure 17. The roller is too small to evaluate the heading controller as the target angle is too small and is actuated during a too short period of time. To evaluate if the heading controller is functioning correctly it needs to be tested outdoors with more open space. An unknown bug when running the simulation environment made the simulated bicycle behave erratically up to this point requiring to add a derivative constant to achieve a stable heading controller. The issue was not found but the behaviour changed without notice and the final parameter of −0.4 that ran on the bicycle on the roller behaved similarly in simulation with slight oscillations.

(27)

Lean angle Steering setpoint Lean setpoint Yaw angle 0 2 4 6 8 -10 -8 -6 -4 -2 Time (s) 18 20 22 -24 26 28 30 32 Angle (degr ees)

Figure 17: Reference of how the balance controller control the bicycle on its own. Some small changes in reference angle is done to keep the bicycle from drifting to the edge of the roller

7.4

45 degree turn

45 degree turn in simulation

0 20 40 60 X (m) -35 -30 -25 -20 -15 -10 -5 0 Y (m) Reference path Bicycle path 0 5 10 15 20 Time (s) -50 -40 -30 -20 -10 0 10 Angle (degr ees) Path heading Bicycle Yaw

Figure 18: Simulated path using a heading controller to take a 45-degree turn. The position tracked in the left figure and the heading tracking in the right image.

Figure 18 shows the heading controller in simulation follow the target heading with a delay until the target heading reaches 45-degrees, where the controller minimises the heading steady-state error. The target path position is overshot in the simulation and contains a steady-state error from the path. The result for when the bicycle is tested outside can be seen in Figure 19. The bicycle follows the target heading through the test with a 10-degree steady-state error from the target heading due to the off-camber turn. The parameters could be tuned to perform better and reduce the steady state error on position as show in Figure 18 using integral of the heading error.

(28)

Instead the use of a lateral controller which would not suffer integration error and can correct the lateral error directly is explored which can be expanded to a lateral+heading controller. An issue not related to the lateral controller is that the bicycle did not accelerate fast enough to reach the target 14km/h before the curve ended. The power and acceleration to the propulsion motor have been increased to reach the target velocity faster for future tests. Next step is to add lateral control based on position error and test the functionality before going into fine-tuning.

45 degree turn outside on bicycle

840 845 850 855 Time (s) -5 -4 -3 -2 -1 0 1 2 3 Angle (degr ees) Lean angle Lean setpoint 840 845 850 855 Time (s) -50 -40 -30 -20 -10 0 10 20 30 40 50 Angle (degr ees) Bicycle Yaw Path heading

Figure 19: Bicycle taking a 45-degree 20m radius off camber turn outside with a heading controller. Left image contains the lean setpoint which is the output from the heading controller and the responding lean angle of the bicycle during the test. The right image contain the target path heading and the bicycle tracking the target path during the turn.

(29)

7.5

Lateral control 14km/h

Lateral control at 14km/h 302 304 306 308 310 312 314 316 Time (s) -8 -6 -4 -2 0 2 4 Lateral error 302 304 306 308 310 312 314 316 Time (s) -8 -6 -4 -2 0 2 4 Lean setpoint Lean angle Steering setpoint Angle (degr ees) Dist ance (m)

Figure 20: Lateral control on a straight road. Autobike is given a light push at 310 and is taken over by the operator at 315 before it hits the road curb when the controller does not correct the lateral deviation.

The results from the lateral controller test are shown in Figure 20 and an image from the test is shown in Figure 21. The bicycle follows the straight path and is given a push at 310s, but the lateral controller could not recover the drift and have to be taken over by the human operator before hitting the road curb. The bicycle is tuned for a velocity at 14km/h which requires the person operating the bicycle to run beside it and being ready to grab the bicycle at that velocity. Imperfections in the road surface also made the front wheel bounce off the ground and the bicycle risking instability. To make it easier and safer to operate the bicycle in the area, tuning the bicycle balance controller to run at a lower velocity needs to be done to allow the person operating the bicycle to jog beside it instead of running.

7.6

10km/h balancing

The bicycle can balance at 10km/h using both new gains sets as seen in Figure 22. Gain set 2 in Table 2 observed fewer oscillations than set 1 when driving outdoors over uneven road imperfections or when the target lean angle is changing.

(30)

Figure 21: An image of the instrumental bicycle driving using lateral controller to follow a path straight set in the middle of the road

90 95 100 105 110 Time (s) -5 0 5 Angle (D egrees)

Gain set 2 balancing 10km/h

Lean angle Lean setpoint 75 80 85 90 95 Time (s) -5 0 5 Angle (D egrees)

Gain set 1 balancing 10km/h

115 85

Lean angle Lean setpoint

Figure 22: Balancing comparison between the two set of balancing PID parameters at a velocity of 10km/h. The target lean angle is changed by the operator to control the direction of the bicycle

The balance Labview PID output saturation with anti-windup suitable to use as an output limiter because after hitting the output limit from the balance controller, then when the bicycle roll is back at 0 the steering output is offset as much as 20◦to 30◦ as if the bicycle was leaning. It is not a problem when using a balance controller but if a path tracker controller could achieve the saturation if it deviates from the path. Test using an external output saturation and remove the PID internal saturation and evaluate if an external saturation suffers the same issue when there is no anti-windup.

(31)

7.7

Lateral control 10km/h

The result of driving the bicycle along a straight path and being pushed off the path halfway is shown in Figure 23 and 24. The bicycle managed to stay with an RMSE of 0.675m and standard deviation of 0.371 from the path driving outdoors compared to an RMSE of 0.108 and standard deviation of 0.074 in simulation. Autobike recovers after being pushed off the path but the bicycle reached the end of the road before the bicycle was able to cross the path again and possibly overshoot. Lateral control at 10km/h 108 110 112 114 116 118 120 122 124 -10 -5 0

5 Steering setpoint (degrees)

Lean setpoint (degrees) Lateral error (m)

Time (s)

Figure 23: Bicycle taken straight path outside using lateral control. Halfway down the road at 116s the bicycle got a push to see how it recovers. Lean angle could not be logged during this test so steering angle is used to highlight the when the push occurs

Issues did arise with the test with the data logging, as in this test roll angle was not being updated and Y position lost a lot of data. Luckily for this test, X position is the important variable to know and the Y position of the bicycle in could use the current path Y position as they should be within centimetres of each other. The test records 24 variables at 100Hz and some of the loss of data might be because of the number of variables and several different loops are affected with loss when recording data. The aim is to reduce the number of log variables by half to 12 as loss of the recorded position data would invalidate future tests when following paths. For the next test, PID parameters shall be tested and improved in simulation to find gains for a better path controller.

(32)

Position using lateral control at 10km/h -10 -8 -6 -4 -2 0 2 4 6 8 10 X (m) 0 10 20 30 40 50 60 Y (m) Simulation test -10 -8 -6 -4 -2 0 2 4 6 8 10 X (m) 0 10 20 30 40 50 60 Y (m) Outside test Reference path Bicycle path Reference path Bicycle path

Figure 24: On the left is the bicycle taking straight path in simulation without a disturbance and right is the bicycle outside using lateral control, actual deviation from path after a push from the operator.

(33)

7.8

Tuning lateral path controller

The result of lateral only controller tuning process in simulation

P

l

I

l

D

l

45

turn

radius = 10m

Straight 100m

180

turn

radius = 15m

RRT path

Note

0.6

0

0

3.958

0.108

4.177

4.583

0.2

0

0

6.749

0.189

10.287

10.175

0.8

0

0

3.201

0.090

3.445

4.930

1

0

0

2.734

0.081

2.935

4.319

1

0

0.1

2.562

0.071

2.848

3.807

1

0

0.5

2.072

0.048

2.637

2.976

1

0

1

1.684

0.035

2.518

2.469

1

0.1

1

2.137

0.051

1.606

3.200

0.5

0

1

3.100

0.069

4.589

4.129

2

0

1

0.816

0.018

1.300

1.388

2

0

0.5

1.069

0.025

1.353

1.678

2

0

1.5

0.630

0.236

1.136

1.063

O

3

0

1

0.489

0.167

1.768

1.241

U

2.5

0

1

0.637

0.015

1.043

1.166

2.5

0.1

1

0.703

0.016

0.659

1.225

2.5

0.2

1

0.802

0.019

0.587

1.347

3

0.2

1

0.580

0.175

0.477

1.392

O

2.8

0.2

1

0.680

0.017

0.513

1.224

2.8

0.2

1.2

2.659

0.340

1.617

8.622

U

2.8

0.1

1.2

0.387

1.932

0.546

0.835

U

2.8

0.3

1

0.779

0.020

0.497

1.533

3

0.3

1

0.672

0.718

0.466

1.727

O

2.8

0.1

1

0.607

0.015

0.588

1.112

2.8

0

1

0.559

0.013

0.933

1.056

2.9

0

1

0.538

0.056

0.892

1.022

O

2.8

0

1.1

0.475

0.271

0.770

1.388

O

2.8

0.1

0.5

0.885

0.022

0.652

1.884

2.8

0.1

0.2

1.388

0.046

0.749

2.634

2.8

0.1

0.1

1.688

0.072

0.836

4.413

C

Table 4: An iterative process to produce gains for a lateral only controller, therefore, gains for heading P, I and D is always 0. Note O is oscillations but the bicycles still complete the path without deviating from the path, C is when the bicycle is so unstable it falls over and U is unstable where the bicycle might deviate from the path due to instability but can recover without crashing

As seen in Table 4 for the lateral controller in simulation using only the cross-track error, the controller is highly dependent on the derivative and proportional gain to reduce the RMSE, small integration gain is only effective on reducing steady-state error on long sweeping turns. From the simulation results, the gains that are used on the bicycle outside is planned to be set 1 in and an optional set 2, both can be seen in Table 2.

(34)

Simulation set 1 Simulation set 2 reduced Gain: Pl 2.8 1

Gain: Il 0.1 0.1

Gain: Dl 1 1

Table 5: Matlab PID gains lateral only control.

Outdoor environment test results

When using set 1 the bicycle is unstable with heavy oscillations of the steering angle as seen in Figure 25. After replacing the controller parameters to set 2 there are still steering angle oscillations seen by Figure 26. For both sets of parameters, the lean setpoint oscillates up and down only limited by the 75 degrees/s rate limiters in the balance controller and destabilise the bicycle at the risk of the bicycle falling over.

Lateral only path tracker using simulation set 1

-20 -10 0 10 20 30 -2 -1 0 1 2 3 Lean angle Steering setpoint Lean setpoint 4 40 Lateral error 100 101 102 103 104 105 100 101 102 103 104 105 Time (s) Time (s) Angle (degr ees) Dist ance (m)

Figure 25: Tuned lateral controller with using controller set 1 from Table 5. The linear increase and decrease of the steering and lean set-point are due to the balance controller hits the 75 degrees/s rate limiter on input and output.

Figure

Figure 2: Visualisation of the bicycle and the variables. Direction of the arrow for angles is in positive direction
Figure 3: Test cases that are evaluated in simulation with the goal of run outside on Autobike offers a straight path and one curve but it is too small for testing most of the simulation test cases.
Figure 4: Instrumental bicycle used from project Autobike. Electronics contain main computer, motor controller, steering motor and radio receiver.
Figure 5: The structure of the physical bicycle controllers and feedback.
+7

References

Related documents

Stöden omfattar statliga lån och kreditgarantier; anstånd med skatter och avgifter; tillfälligt sänkta arbetsgivaravgifter under pandemins första fas; ökat statligt ansvar

46 Konkreta exempel skulle kunna vara främjandeinsatser för affärsänglar/affärsängelnätverk, skapa arenor där aktörer från utbuds- och efterfrågesidan kan mötas eller

The increasing availability of data and attention to services has increased the understanding of the contribution of services to innovation and productivity in

I dag uppgår denna del av befolkningen till knappt 4 200 personer och år 2030 beräknas det finnas drygt 4 800 personer i Gällivare kommun som är 65 år eller äldre i

Det har inte varit möjligt att skapa en tydlig överblick över hur FoI-verksamheten på Energimyndigheten bidrar till målet, det vill säga hur målen påverkar resursprioriteringar

Detta projekt utvecklar policymixen för strategin Smart industri (Näringsdepartementet, 2016a). En av anledningarna till en stark avgränsning är att analysen bygger på djupa

The highest peak angular velocity was found for impact location “Side” and impact direction “2” for all helmet designs except Helmet 2 where the highest peak value was found

Industrial Emissions Directive, supplemented by horizontal legislation (e.g., Framework Directives on Waste and Water, Emissions Trading System, etc) and guidance on operating