Keywords

1 Introduction

Modern traffic safety relies heavily on Advanced Driver Assistance Systems (ADAS). Testing these systems often requires specific scenarios that include a cyclist target to ensure safety and repeatability. To address the challenges of testing ADAS in cyclist scenarios, a bicycle robot with self-balancing and path-tracking capabilities has been developed. Compared to existing solutions with a stable moving robot platform [1], this bicycle robot is inherently unstable and hence will exhibit more natural leaning behavior.

Obtaining a reliable model usually requires measuring and computing physical parameters. However, such methods require additional tools and time to dismantle the bicycle and measure its individual parts. In contrast, this paper adopts an alternative approach: using system identification techniques to estimate these model parameters from experimental data.

Gray-box identification offers an advantage in this context. It employs a model structure informed by physical principles, which can enhance robustness against varying operational conditions. Given its benefits, we apply a gray-box identification method, to compute a bicycle model parameterized by longitudinal speeds. This strategy combines the merits of a physically-informed model with system identification, enabling the identified model to extrapolate dynamics across multiple speeds.

In this paper, we introduce a gray-box identification method to obtain a semi-linear bicycle model. Tests are done in a closed loop and a model with an explicit speed dependency is obtained. The speed-dependent model is then used to derive a controller that achieves a speed independent closed loop using gain scheduling (Fig. 2).

Fig. 1.
figure 1

Bike schematics

Fig. 2.
figure 2

Schematic Block of the Control loops

2 Method

The steering angle of the bicycle is assumed to be controlled perfectly. Hence, we do not need to consider models that include the interaction between the leaning angle and the steering torque. Instead we adopted a point-mass model from [2] for its simplicity and relevance to our actuator settings, as shown in Fig. 1. The bicycle’s roll dynamics from steering angle \(\delta \) to roll \(\varphi \) are given by, assuming small caster,

$$\begin{aligned} J_{xx} \frac{d^2 \varphi }{d t^2} - m g h_{CM} \varphi = \frac{J_{xz} v \sin {(\lambda )}}{b} \frac{d \delta }{d t} + \frac{m v^2 h_{CM} \sin {(\lambda )} }{b} \delta , \end{aligned}$$
(1)

where \(J_{xx},J_{xz}\) are the inertia with respect to the xz-axes and x-axes. Other parameters are depicted in Fig. 1. The equation above can be recast to a LTI transfer function for a constant speed with the structure,

$$\begin{aligned} G_{\dot{\varphi } \dot{\delta }} (s, v) = \frac{A_0 v s + A_1 v^2}{s^2 + B_0} \end{aligned}$$
(2)

where s is the Laplace operator and \(A_i,B_i\) are constant coefficients. This equation describes the roll dynamics, i.e., \(G_{\dot{\varphi } \dot{\delta }}(v)\) in Fig. 1.

To identify the parameters of the roll dynamics in (2), identification experiments were conducted in closed loop. To mitigate biases induced by closed loop, periodic excitation signals were used and frequency responses are collected [3]. This was done by applying these periodic signals to the reference \(\varphi _{ect}\) and noise to \(\dot{\delta }_{ect}\). Further, to use the frequency response for our unstable system \(G_{\dot{\varphi } \dot{\delta }}\), the definition of transfer functions are also extended to include the imaginary axis, since the imaginary axis is not in its region of convergence.

A next step in the identification process was to form empirical transfer function estimate (ETFE) \(\hat{F}(j \omega , v_i)\) based on the measured tests,

$$\begin{aligned} \hat{F}(j \omega , v_i) = \frac{1}{P_i} \sum \limits ^{l=P_i}_{{l=1}} \frac{\mathcal {F} \{\hat{\dot{\varphi }}_{[{l}]}(j \omega , v_i) \} }{\mathcal {F} \{ \hat{\dot{\delta }}_{[{l}]}(j \omega , v_i) \}} = {R} (j \omega , v_i) + j {I}(j \omega , v_i) \end{aligned}$$
(3)

where subscript l denotes the lth response out of \(P_i\) periodic responses conducted at speed \(v_i\). \(\mathcal {F} \{ x \}\) denotes the Fourier transform of time series data x, and R and I denote the coefficients of real and imaginary components, respectively. Such an averaged ETFE is asymptotically unbiased if the noise e is Gaussian [3].

A final step in the identification process was to use the obtained ETFE in (3) to fit the model (2).

To minimize the difference between the identified model \(G_{\dot{\varphi } \dot{\delta }}(j \omega , v)\) and the empirical transfer function \(\hat{F}(j \omega , v_i)\), a cost function of frequency responses \(\varepsilon (j \omega , v)\) can be defined

$$\begin{aligned} \varepsilon (j \omega , v) &= \hat{F}(j \omega , v) - G_{\dot{\varphi } \dot{\delta }}(j \omega , v) = \hat{F}(j \omega , v_i) - \frac{N(j \omega , v)}{D(j \omega , v)} \end{aligned}$$
(4)
$$\begin{aligned} D \varepsilon &= D \hat{F} - N = a(j \omega , v) + jb(j \omega , v) \end{aligned}$$
(5)

where N and D are numerator and denominator of the transfer function in (2).

With a total of n experiments at speeds \(v_i, i \in \mathcal {Z^+}\) and each containing \(m+1\) frequency points in frequency responses, we may sum the cost function \(\varepsilon (j \omega , v)\) over all the experiments

$$\begin{aligned} E &= \sum \limits ^n_{i=1} \sum \limits ^m_{k=0} [a^2(j \omega _k, v_i) + b^2(j \omega _k, v_i)] . \end{aligned}$$
(6)

Here k denotes the index of the frequency points in Fourier Transformation of the experiment data and i denotes the index of speeds. For simplicity in notation, variables to the functions \((j \omega _k, v_i)\) will be omitted henceforth. We notice that, (6) is a weighted cost function of the difference between the identified model \(G_{\dot{\varphi } \dot{\delta }}\) and the empirical transfer function \(\hat{F}\). Therefore, we can minimize (6) with respect to all unknown coefficients - \(A_i\)’s and \(B_i\)’s in the transfer function

$$\begin{aligned} \frac{\partial E}{ \partial A_i} = 0 , \quad \frac{\partial E}{ \partial B_i} = 0 . \end{aligned}$$
(7)

To minimize the differences (6) over all the experiments spanned in a speed range \(\{ v_1, ... , v_{n} \}\), we construct the equations into a linear regression form. Define intermediate variables \(\lambda _h\), \(S_h\), \(T_h\) and \(U_h\)

$$\begin{aligned} \lambda _h = \sum \limits ^m_{k=0} W_k \omega _k^h , S_h = \sum \limits ^m_{k=0} W_k \omega _k^h \hat{R}_k , T_h = \sum \limits ^m_{k=0} W_k\omega _k^h \hat{I}_k , U_h = \sum \limits ^m_{k=0} W_k \omega _k^h (\hat{R}_k^2 + \hat{I}_k^2) \end{aligned}$$

where m denotes the number of frequency points in a frequency response. \(W_k\), which provides design freedom compared to the weight D from problem construction in (5), is a user-defined weight for individual frequency points.

Substitute these variables and rewrite (7) in matrix form

$$\begin{aligned} \sum \limits ^n_{i=1} \left[ \begin{matrix} 2 \lambda _0 v_i^4 & 0 & -2 S_0 v_i^2 \\ 0 & 2 \lambda _2 v_i^2 & -2 T_1 v_i \\ -2 S_0 v_i^2 & -2 T_1 v_i & 2 U_0 \\ \end{matrix} \right] \left[ \begin{matrix} A_0 \\ A_1 \\ B_0 \\ \end{matrix} \right] & = \sum \limits ^n_{i=1} M(v_i) N \nonumber \\ =\,\sum \limits ^n_{i=1} \left[ \begin{matrix} -2 S_2 v_i^2 \\ -2 T_3 v_i \\ 2 U_2 \\ \end{matrix} \right] & = \sum \limits ^n_{i=1} C(v_i) . \end{aligned}$$
(8)

Further, experiments can also be weighted individually

$$\begin{aligned} \sum \limits ^n_{i=1} W_i M(v_i) N = \sum \limits ^n_{i=1} W_i C(v_i) \end{aligned}$$
(9)

where \(W_i\) is the user-defined weight for individual speeds \(i \in \{ 1, ... , n \}\). This complex linear curve fitting problem is thus solvable in a weighted least square formulation. The weights for individual experiments and frequency points, i.e. \(W_i\) and \(W_k\), may be used as a tuning parameter, depending on the number of periods in each experiment and frequency range of confidence.

Based on the derived parameter dependent LTI model of the roll dynamics, a gain-scheduled PD controller was designed. The design criteria was a speed independent closed loop performance for a range of speeds. Specifically, \(K_{I} (v)\) and \(K_{O} (v)\) are computed, such that inner balancing and outer roll tracking loop in Fig. 1 have speed-independent bandwidths.

3 Result

On the bicycle presented in Fig. 3, identification experiments have been conducted, at speeds of 2.2, 2.4, 2.6, 2.8 m/s. Although these experiments were conducted without a human dummy, our algorithm is prepared for scenarios involving a dummy, which can be modeled as a mass rigidly attached to the saddle. Periodic multisine signals up to 25 Hz are chosen for \(\varphi _{ect}\) and \(\dot{\delta }_{ect}\) to control the excitation frequency range. After the decay of initial transients, the periodic responses are processed following (3). Table 1 summarizes the number of identification periods and Fig. 3 visualizes the averaged frequency responses at each speed. It is noteworthy that, in lower frequency range, a clear dependency can be seen between the magnitudes of frequency responses and the speeds. At higher frequencies, this dependency dies out and it might be attributed to other system dynamics in the control loop, e.g. sensors.

Substituting the computed averaged empirical transfer functions \(\hat{F}(j \omega , v_i) = \bar{G}_i(j \omega )\) and letting the weights \(W_k\), \(W_i\) be identity for simplicity, a model is identified:

$$\begin{aligned} \hat{G}_{\varphi \delta }(s, v) = \frac{0.8285 v s + 1.9699 v^2}{s^2 - 20.2663} \end{aligned}$$
(10)

To evaluate this model and with a rough approximation of \(D = - J_{xz} \approx - m a h_{CM}\) and \(J \approx m h_{CM}^2\), a comparison between the identified parameters of the roll dynamics and direct measurements of center of gravity is given in Table 2. It can be observed that the differences are small in magnitude.

Based on the identified model, we compute \(K_{I}(v)\) and \(K_{O}(v)\) to limit the closed-loop bandwidth of the inner balancing loop to be 1.5 Hz and the outer roll-tracking loop 0.15 Hz respectively.

Against a same step references of \(\pm 3 ^{\circ }\), this gain-scheduled PD controller was tested on the bicycle robot. For comparison, a speed-independent P-D controller is tested as well, referred to as conventional P-D controller. Figure 3 illustrates the roll-tracking performance. While both the gain-scheduled (Blue) and conventional P-D controllers (Red) performed similarly at the higher speed, the gain-scheduled controller has better performance at the lower speed. This highlights the limitations of conventional controllers and confirm the practical need of our gain-scheduled approach. With the same roll reference, the gain-scheduled controller is further tested at an even lower speed of 1.7 m/s, visualized in Fig. 6. Despite of constraints in the steering motor and IMU signal-to-noise ratio, the gain-scheduled controller stabilzed the bicycle, showing the potential of speed extrapolation (Figs. 5 and 4).

Table 1. The experiment profile
Fig. 3.
figure 3

Figure to the right: the averaged empirical transfer function (3)

Table 2. The calculated physical parameters illustrated in Fig. 1
Fig. 4.
figure 4

Bike modules overview

Fig. 5.
figure 5

Figure to the right: Tests of the Gain-scheduled controller (Blue) and conventional P-D controller (Red) at 2.4 and 3.0 m/s with \(\varphi _{ref} = \pm 3^{\circ }\)

Fig. 6.
figure 6

Experiment with the extrapolated Gain-scheduling controller at lower speeds

4 Conclusions

An approach to obtain a gain scheduled controller for a balancing bicycle robot using grey box identification is presented. The performance of the controller is illustrated on a prototype bicycle robot. The gray box identification employs periodic excitation signal to asymptotically remove the bias and the excitation frequency ranges are tailored with multisine excitation signals.

Future work will focus on enhancing controller robustness and adapting the model for changing conditions, e.g., loading different human dummies. Besides, adaptive control and online identification based on dual-Youla method may be explored as it fits our purpose well [5].