None
The linear fourth-order ordinary differential equation model we will develop here uses many of the same assumptions as Meijaard, Papadopoulos, Ruina, and Schwab ( 2007), which are essentially consistent with the work of Whipple in 1899. These include no longitudinal acceleration, symmetry of the bike in the XZ plane, two independent frames (front fork and rear frame with rigidly attached rider), knife-edged tires, no tire slip, and small perturbations from steer and roll angles of zero (straight running). The model developed here is simpler than the one presented in Meijaard et al., in that we will assume that the front and rear frames can be modeled simply as point masses.
Note: I wrote an online, interactive version of this model that you can try here
This model explains self-stabilization (hands-free riding) in bicycles and motorcycles reasonably well. It also gives a motorcycle or bicycle designer a good idea of how oscillatory the bike will be in response to disturbances (wind, pebbles, curbs) and rider inputs (lean and/or steer inputs). The model's description of motorcycle dynamics is also sufficient for designing a self-driving steering controller, even for relatively complex path-following controllers. Lots of the nuanced effects of motorcycle handling and stability are captured in this model, even though it is quite simplified, ignoring tire dynamics and nonlinearities of any kind.
Meijaard et al. (2007) is a comprehensive review of the linear models used to describe bicycle and motorcycle dynamics in the 20th century (and into the first part of the 21st). One might ask: why re-hash the derivation of the Whipple model yet again?
The answer is that when I was an undergraduate and first became interested in motorcycle dynamics (around the time that Meijaard et al. was published) I felt like the papers in the literature skipped some important steps in the derivation for brevity. To someone well-versed in classical mechanics, the 'gaps' in the derivations presented are OK, but to someone who is less comfortable or experienced, especially with Lagrangian, Hamiltonian, and other energy-based approaches, any missing steps can be unsettling at best, and anxiety-inducing at worst, especially when attempting to reproduce a derivation to deepen one's understanding.
I'm definitely someone who needs time and space to fully "digest" mathematical models, and I suspect others feel this way as well. To fully digest a mathematical model, I need to know where every term came from, and I need to have some physical intuition for each piece of the model, which is hard when steps are omitted from a derivation.
This notebook (and its supporting notebooks) do everything possible to avoid "skipping steps" or glossing over parts of the model. There are still some pieces that the reader will have to do on their own, but they are limited to the intermediate steps in taking derivatives or moving terms around in an equation using simple algebra. I have also decided to color-code terms so that in the final version of the model, it is clear what physical process is responsible for each term. This may make the model more cumbersome to write out when compared to the form presented in Meijaard et al. (2007), but I believe it strengthens the reader's understanding of what is responsible for the complexities of bicycle and motorcycle behavior.
Further, I am not a fan of the SAE vehicle-fixed coordinate system, which is what the Meijaard et al. (2007) paper uses. I prefer the ISO vehicle-fixed coordinate system, with $x$ forward, $y$ left, and $z$ up. This means that you will find that some terms this version of the model might differ from what you'll find elsewhere in the literature. That's ok-- these sign differences are because of the change in coordinate system definition.
Finally, I have included a tutorial in this page that shows how the model can be transformed from "MDK" or "Mass Spring Damper" form into "State Space" form, which is necessary if one whishes to design a control algorithm to make a two-wheeler self-stabilize or drive itself.
I don't know, but I can try!
The simplest version of the story is that the geometry and mass properties of the front frame (fork/front wheel) are such that the bike steers itself "into the lean" whenever there is a disturbance that causes the bike to become off-balance.
More specifically, when the bike initially steers due to some disturbance or rider input, the line of support between its two tires' contact with the ground moves out from under the bike's mass center. This, along with centrifugal reactions on the rear frame's mass center, cause the potential energy of the bike to begin to turn into kinetic energy in the roll (lean) direction as the bike begins to fall over.
Then, this roll motion creates torques on the front frame (centrifugal, tire contact, and gyroscopic) that, in summation, direct it to steer the opposite direction of its initial motion (into the fall rather than away from it). These torques redirect some of that kinetic energy as the bike yaws (turns), the front frame steers, and the line of support between the bike's two wheels moves back under its center of mass. This stands the bike back up, "refilling the well" of potential energy using the bike's (constant) forward speed.
Now, all of this only happens if the bike's geometry and mass parameters are 'just right,' and the bike's speed is 'just right.' It's a delicate balance between the energy the bike has available and the front frame's ability to redirect that energy in a way that counteracts gravity 'just enough' without overcompensating. Too little of ths 'automatic countersteering action' of the front frame, and the bike falls over. Too much, and the bike will overcorrect, creating oscillations that may grow and cause... the bike to fall over.
Of course, when I say 'just right,' there's actually a range of parameters and speeds that are 'just right enough,' which is why sometimes a bike can be self-stable, but oscillate a lot, or be difficult to turn, etc. Unfotunately, uderstanding the nuances of what changes cause what effects either requires the math in the rest of this tutorial, or a ton of empirical experience!
So, if you decide to read on, try to keep this basic balance in mind as you look at each term in the equations, especially those that have to do with torques about the front (steering) frame.
The coordinate system used for our bicycle and associated dimensions are presented below in Figure 1.
Figure 1. Coordinates and dimensions
In addition to the "main" derivation of the model's equations of motion using LaGrange's method, several supporting notebooks provide derivations and/or context for specific "pieces" of the model. The notebooks are separated to avoid cluttering this derivation with "tangents" that aren't a direct part of LaGrange's method for deriving the model's equations of motion. While these "tangents" would distract from the rhetorical quality of the current notebook, they are very important for understanding the derivation and the eventual final model, so they are referenced in the text of this notebook where they are most relevant to read. However, they are also listed below for easy reference. I suggest reading these notebooks as they come up in the derivation rather than trying to read them all before proceding. You can also skip them entirely if you're not particularly interested in how the expressions these notebooks develop are derived.
If you have taken my ES103 course, LaGrange's method is a fairly manageable next step in your tool box for developing dynamic models of mechanical systems. An introduction to the method and its relationship to the methods presented in ES103 is given here.
LaGrange's method for developing a system's equations of motion requires the "LaGrangian," or the difference between a system's kinetic and potential energy:
\begin{equation} L \equiv T - V \end{equation}
Where $T$ is a system's kinetic energy and $V$ is the system's potential energy, all defined in terms of the system's independent 'generalized coordinates.' For our system, the bike is permitted to roll about its local $x$-axis $\hat{\imath}$, which moves both the front and rear frames together. It is also permitted to "yaw" about the gravitational axis, and the steered frame (front frame) can rotate about the steering axis.
To apply Lagrange's method to the system, we begin by computing the following for each generalized coordinate in $\vec{q} = \left[\phi,\delta,\psi\right]^T$, where $\phi$ is the vehicle's roll, $\delta$ is the steer angle, and $\psi$ is the yaw angle.
\begin{equation} \frac{d}{dt}\left( \frac{\partial T}{\partial \dot{q_i}} \right) - \left( \frac{\partial T}{\partial {q_i}} \right) + \left( \frac{\partial V}{\partial {q_i}} \right) = \tau_i \end{equation}
In the equation above, the Left-hand side of the equation gives us:
The right-hand side of the equation, $\tau_i$, represents the sum of all "non-conservative" torques acting on the system. These are torques that cause energy to cross the system boundary, and include terms from things like "lossy" frictional torques, or torques from idealized sources of power (in our case, these include torques associated with the bike's forward velocity $U$, since this is assumed to be constant no matter what).
To complete "LaGrange's Method" for the bike, we have to apply Equation 2 for each of our three generalized coordinates:
\begin{equation} \frac{d}{dt}\left( \frac{\partial T}{\partial \dot{\phi}} \right) - \left( \frac{\partial T}{\partial {\phi}} \right) + \left( \frac{\partial V}{\partial {\phi}} \right) = \tau_\phi \end{equation}
\begin{equation} \frac{d}{dt}\left( \frac{\partial T}{\partial \dot{\delta}} \right) - \left( \frac{\partial T}{\partial {\delta}} \right) + \left( \frac{\partial V}{\partial {\delta}} \right) = \tau_\delta \end{equation}
\begin{equation} \frac{d}{dt}\left( \frac{\partial T}{\partial \dot{\psi}} \right) - \left( \frac{\partial T}{\partial {\psi}} \right) + \left( \frac{\partial V}{\partial {\psi}} \right) = \tau_\psi \end{equation}
These three are our "Equations of Motion" for the bike system as defined, so the task is to substitute in the relevant derivatives of the LaGrangian and the non-conservative torques for each. Nominally, these will each include a second derivative and first derivative of one or more of the generalized coordinates along with the generalized coordinates themselves, making each of the three equations of motion second order. This means that without any more information, we'd expect the model resulting from our analysis to be 6th order, since it is comprised of three coupled second-order equations. From an energetic standpoint, this is consistent-- the bike can store potential energy in response to roll and steer in both the front and rear frames. It can also store kinetic energy in the roll and steer directions, along with storing kinetic energy in the yaw direction. If all of those energy storage processes are independent, then a 6th order model is a reasonable expectation.
However: the bike's yaw motion is not independent of its steer motion. In fact, with the assumption of zero tire slip, the bike's yaw motion is fully determined by the steer angle and steer rate. This means that our third second-order equation of motion can be eliminated algebraically, leading to a fourth order model. More on this to follow.
For each generalized coordinate $\vec{q} = \left[\phi,\delta,\psi\right]^T$, we need to compute the derivatives as per LaGrange's equation above. The bike's kinetic energy is derived in this notebook, and the bike's potential energy is derived in this notebook. The two are reproduced below for reference.
\begin{equation} \begin{aligned} T &=& \frac{1}{2}m_r& ( U^2 + a^2\dot{\psi}^2 + h_r^2\dot{\phi}^2 - 2ah_r \dot{\psi}\dot{\phi} )\\ &+& \frac{1}{2}m_f& ( U^2 + x_f^2\dot{\psi}^2 + h_f^2\dot{\phi}^2 + u^2\dot{\delta}^2 - 2x_fh_f\dot{\psi}\dot{\phi} - 2uh_f\dot{\delta}\dot{\phi} + 2x_fu\dot{\delta}\dot{\psi} ) \end{aligned} \end{equation}
\begin{equation} V = m_r g h_r \cos\phi + m_f g \left( \cos\phi \left( b+c - x_f\right)\sin\lambda + \frac{u}{\cos\lambda}\cos\left( \phi - \delta\cos\lambda \right) \right) \end{equation}
Computing the derivatives of kinetic energy $T$ with respect to velocities $\dot{\vec{q}}$ to find terms for Eqn 2 gives the following. Starting with the roll direction:
\begin{equation*} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\phi}} \right) &=& \ddot{\phi}& \left( m_rh_r^2 + m_fh_f^2 \right) \\ &+& \ddot{\delta}&\left(-m_fh_fu\right) \\ &+& \ddot{\psi}&\left( -m_rah_r-m_fx_fh_f\right) \end{aligned} \end{equation*}
Using the kinematic relationship between yaw rate and steer, $\dot{\psi} = \frac{U\sin\lambda}{b}\delta + \frac{c\sin \lambda}{b}\dot{\delta}$, which we derive in the turning kinematics notebook, we can eliminate yaw rate and yaw acceleration from this equation in anticipation of the "Eliminating Yaw" section. Substituting, we can write:
\begin{equation} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\phi}} \right) &=& \ddot{\phi}& \left( m_rh_r^2 + m_fh_f^2 \right) \\ &+& \ddot{\delta}&\left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right) \\ &+& \dot{\delta}&\left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right)\right) \end{aligned} \end{equation}
Computing the same partial derivative in the steer direction, we obtain:
\begin{equation*} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\delta}} \right) &=& \ddot{\phi}& \left( -m_f u h_f \right) \\ &+& \ddot{\delta} &\left( m_fu^2 \right) \\ &+& \ddot{\psi} &\left(m_f x_f u \right) \end{aligned} \end{equation*}
Using the kinematic relationship between yaw rate and steer, $\dot{\psi} = \frac{U\sin\lambda}{b}\delta + \frac{c\sin \lambda}{b}\dot{\delta}$, which we derive in the turning kinematics notebook, we can eliminate yaw rate and yaw acceleration from this equation in anticipation of the "Eliminating Yaw" section. Substituting, we can write:
\begin{equation} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\delta}} \right) &=& \ddot{\phi}& \left( -m_f u h_f \right) \\ &+& \ddot{\delta} &\left( m_f\left(u^2 + \frac{c\sin \lambda}{b} x_f u\right) \right) \\ &+& \dot{\delta} &\left(m_f x_f u \frac{U\sin \lambda}{b}\right) \end{aligned} \end{equation}
Computing the same derivative for the yaw direction, we can write:
\begin{equation*} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\psi}} \right) &=& \ddot{\phi}& \left(-m_rah_r-m_fx_fh_f\right) \\ &+& \ddot{\delta}& \left(m_fx_f u \right)\\ &+& \ddot{\psi}& \left(m_ra^2 + m_fx_f^2 \right) \end{aligned} \end{equation*}
Using the kinematic relationship between yaw rate and steer, $\dot{\psi} = \frac{U\sin\lambda}{b}\delta + \frac{c\sin \lambda}{b}\dot{\delta}$, which we derive in the turning kinematics notebook, we can eliminate yaw rate and yaw acceleration from this equation in anticipation of the "Eliminating Yaw" section. Substituting, we can write:
\begin{equation} \begin{aligned} \frac{d}{dt} \left( \frac{\partial T}{\partial \dot{\psi}} \right) &=& \ddot{\phi}& \left(-m_rah_r-m_fx_fh_f\right) \\ &+& \ddot{\delta}& \left(\frac{c\sin\lambda}{b}\left(m_ra^2+m_fx_f^2\right) + m_fx_f u \right)\\ &+& \dot{\delta}& \left( \frac{U\sin\lambda}{b}\left(m_ra^2 + m_fx_f^2\right) \right) \end{aligned} \end{equation}
Computing derivatives of kinetic energy $T$ with respect to positional changes in the generalized coordinates yields:
\begin{equation} \frac{\partial T}{\partial \phi} = \frac{\partial T}{\partial \delta} = \frac{\partial T}{\partial \psi} = 0 \end{equation}
This means that our coordinate system definition is consistent with one defined in a "Newtonian" coordinate system. These derivatives are typically only nonzero if relative coordinates are used in the list of "generalized coordinates" for the system.
Computing derivatives of potential energy $V$ with respect to changes in each generalized coordinate, and then applying the small angle approximation $\sin\theta \approx \theta$, $\cos \theta \approx 1$ (same as a formal linearization about $\theta = 0$ using the Taylor Series) yields:
\begin{equation} \frac{\partial V}{\partial \phi } = \phi \left(-m_r g h_r - m_f g h_f\right) + \delta m_f g u \end{equation}
\begin{equation} \frac{\partial V}{\partial \delta } = \phi \left(m_f g u\right) - \delta \left(m_f g u\right) \end{equation}
\begin{equation} \frac{\partial V}{\partial \phi } = 0 \end{equation}
Note that each non-zero derivative may contain groups of terms multiplied by a generalized coordinate, its first derivative, or its second derivative.
Taking a pause here to substitute what we now know into Eqn 3, we get a partial look at our equation of motion for the roll direction:
\begin{equation} \begin{aligned} &\ddot{\phi} \left( m_rh_r^2 + m_fh_f^2 \right)\\ +& \ddot{\delta}\left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right)\\ +& \dot{\delta}\left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right)\right)\\ +& \phi \left(-m_r g h_r - m_f g h_f\right) \\ +& \delta m_f g u\\ =& \tau_\phi \end{aligned} \end{equation}
Performing a similar substitution for Eqn 4, we get a partial look at our equation of motion for the steer direction:
\begin{equation} \begin{aligned} &\ddot{\phi} \left( -m_f u h_f \right) \\ +& \ddot{\delta} \left( m_f\left(u^2 + \frac{c\sin \lambda}{b} x_f u\right) \right) \\ +& \dot{\delta} \left(m_f x_f u \frac{U\sin \lambda}{b}\right) \\ +& \phi \left(m_f g u\right) \\ +& \delta \left(-m_f g u\right) \\ =& \tau_\delta \end{aligned} \end{equation}
Finally, performing the same analysis for the yaw direction in Eqn 5 yields:
\begin{equation} \begin{aligned} &\ddot{\phi} \left(-m_rah_r-m_fx_fh_f\right) \\ +& \ddot{\delta} \left(\frac{c\sin\lambda}{b}\left(m_ra^2+m_fx_f^2\right) + m_fx_f u \right)\\ +& \dot{\delta} \left( \frac{U\sin\lambda}{b}\left(m_ra^2 + m_fx_f^2\right) \right)\\ =& \tau_\psi \end{aligned} \end{equation}
In our model, the "non-conservative" torques come from:
The links above lead to notebooks where these are derived for our model, so the results are only summarized here. Reading the linked notebooks will give you an in-depth look at where these come from. In terms of our LaGrangian derivation, we will take "non-conservative" to mean that the torque will cause energy to cross the system boundary, either adding energy from a "source of infinite power" (such as gravity effects not captured by the potential energy equation, the vehicle's centripetal acceleration from its constant speed and curved path, or gyroscopic reactions resulting from a wheel's constant angular velocity).
For the remainder of this notebook, we will be color-coding terms from each of these effects. We will write:
\begin{equation} \begin{aligned} \tau_\phi &=& \color{blue}{\tau_{\phi,TF}} + \color{red}{\tau_{\phi,DA}} + \color{green}{\tau_{\phi,GY}} + &T_{in,\phi} \\ \tau_\delta &=& \color{blue}{\tau_{\delta,TF}} + \color{red}{\tau_{\delta,DA}} + \color{green}{\tau_{\delta,GY}}+ &T_{in,\delta} \\ \tau_\psi &=& \color{blue}{\tau_{\psi,TF}} + \color{red}{\tau_{\psi,DA}} + \color{green}{\tau_{\psi,GY}}& \end{aligned} \end{equation}
where "TF" indicates that the torque is from "tire forces," DA indicates that the torque is from D'Alembert reactions, and GY indicates that the torque is from a gyroscopic reaction. $T_{in}$ torques for the $\phi$ and $\delta$ directions are applied torques from the rider and/or from disturbances.
Based on the analyses in the linked notebooks, we can combine the non-conservative torques from each effect about the $\hat{\imath}$ axis to write $\tau_{\phi}$ as:
\begin{equation*} \begin{aligned} \tau_{\phi} &= \color{blue}{-\delta \frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)}\\ &+ \color{red}{\dot{\psi}U\left(m_f h_f + m_r h_r\right)} \\ &+ \color{green}{\delta \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) + \dot{\delta}\left(U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) + U\frac{J_{yyf}}{R_{fw}}\sin\lambda \right)} \end{aligned} \end{equation*}
Combining terms multiplied by each generalized coordinate and derivative yields:
\begin{equation} \begin{aligned} \tau_{\phi} &= \delta \left(\color{blue}{ -\frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)}+\color{green}{ \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)}\right)\\ &+ \dot{\psi} \color{red}{ U\left(m_f h_f + m_r h_r\right)} \\ &+ \dot{\delta}\color{green}{\left(U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) + U\frac{J_{yyf}}{R_{fw}}\sin\lambda \right)} \end{aligned} \end{equation}
Similarly, we can write $\tau_\delta$ as:
\begin{equation*} \begin{aligned} \tau_\delta =& \color{blue}{-c\sin\lambda \left(F_f + \frac{g\left(m_ra+m_f x_f\right)}{b}\left(\phi - \delta \cos \lambda \right)\right)} \\ & \color{red}{-m_f u U \dot{\psi}} \\ & \color{green}{ -\dot{\delta} U\frac{J_{yyf}}{R_{fw}}\frac{c\sin\lambda\cos\lambda}{b} - \delta \frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b} - \dot{\phi}U\sin\lambda\frac{J_{yyf}}{R_{fw}} }\\ &+ T_{in,\delta} \end{aligned} \end{equation*}
grouping terms by generalized coordinate yields:
\begin{equation} \begin{aligned} \tau_\delta =&\phi& \left(\color{blue}{-\frac{gc\sin\lambda\left(m_ra+m_fx_f\right)}{b}} \right)\\ +& \delta & \left(\color{blue}{\frac{cg\sin\lambda\cos\lambda\left(m_ra+m_fx_f\right)}{b}} - \color{green}{\frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b}} \right) \\ +& \dot{\phi}& \left(\color{green}{-U\sin\lambda\frac{J_{yyf}}{R_{frw}} }\right)\\ +& \dot{\delta}& \left( \color{green}{ U\frac{J_{yyf}}{R_{frw}}\frac{c\sin\lambda\cos\lambda}{b} } \right)\\ +& \dot{\psi}& \left( \color{red}{-m_fuU\dot{\psi}} \right) \\ +& & \color{blue}{-c\sin\lambda F_f}\\ +&&T_{in,\delta} \end{aligned} \end{equation}
Note that $F_f$ in this equation, the lateral tire force on the front tire, is an unknown. It doesn't directly contain a term multiplied by a generalized coordinate or derivative. However, it also shows up in the $\tau_\psi$ equation! It is technically a "constraint force" in the language of Lagrangian mechanics, and is a result of the "non-holonomic" constraint of the tires' Ackermann steering behavior on the road surface.
Writing $\tau_{\psi}$ in the same manner as the other two sets of non-conservative forces, we get:
\begin{equation} \tau_\psi = \color{blue}{F_f b} - \dot{\psi}\color{red}{U\left(m_fx_f + m_r a\right)} + \dot{\phi} \color{green}{\left(-U\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)\right)} + \dot{\delta}\color{green}{U\frac{J_{yyf}}{R_{fw}}\cos \lambda} \end{equation}
To bookmark where we are, we will substitute the non-conservative torques (Eqns 19-21) into our equations of motion (Eqns 15-17) and move all terms multiplied by our generalized coordinates (and their derivatives) to the left-hand side of the equations. Beginning with Eqn 15 and substituting in Eqn 19, we get:
\begin{equation} \begin{aligned} &\ddot{\phi} \left( m_rh_r^2 + m_fh_f^2 \right)\\ +& \ddot{\delta}\left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right)\\ +& \dot{\delta}\left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right)- \color{green}{U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) - U\frac{J_{yyf}}{R_{fw}}\sin\lambda}\right)\\ +& \dot{\psi}\left( \color{red}{ -U\left(m_f h_f + m_r h_r\right)}\right) \\ +& \phi \left(-m_r g h_r - m_f g h_f\right) \\ +& \delta \left(m_f g u+ \color{blue}{ \frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)}-\color{green}{ \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)}\right)\\ =& T_{in,\phi} \end{aligned} \end{equation}
Note that the colored terms from $\tau_\phi$ have switched signs, since they have moved from the right-hand side of Equation 15 to the left-hand side. Performing a similar substitution, Working Eqn 20's expression for $\tau_\delta$ into Eqn 16 for the $\delta$ direction yieds:
\begin{equation} \begin{aligned} &\ddot{\phi} \left( -m_f u h_f \right) \\ +& \ddot{\delta} \left( m_f\left(u^2 + \frac{c\sin \lambda}{b} x_f u\right) \right) \\ +& \dot{\phi} \left(\color{green}{U\sin\lambda\frac{J_{yyf}}{R_{frw}}}\right)\\ +& \dot{\delta} \left(m_f x_f u \frac{U\sin \lambda}{b}- \color{green}{ U\frac{J_{yyf}}{R_{frw}}\frac{c\sin\lambda\cos\lambda}{b} }\right) \\ +& \dot{\psi}\left(\color{red}{m_f u U }\right)\\ +& \phi \left(m_f g u + \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}} \right) \\ +& \delta \left(-m_f g u - \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}\cos \lambda}+ \color{green}{\frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b}} \right) \\ +& \color{blue}{c\sin \lambda F_f }\\ =& T_{in,\delta} \end{aligned} \end{equation}
Finally, Substituting Eqn 21's expression for $\tau_\psi$ into Eqn 17, and moving all non-conservative torque terms except the $F_f$ term (more on this in the next section) to the left-hand side yields:
\begin{equation} \begin{aligned} &\ddot{\phi} \left(-m_rah_r-m_fx_fh_f\right) \\ +& \ddot{\delta} \left(\frac{c\sin\lambda}{b}\left(m_ra^2+m_fx_f^2\right) + m_fx_f u \right)\\ +& \dot{\phi} \color{green}{\left(U\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)\right)}\\ +& \dot{\delta} \left( \frac{-U\sin\lambda}{b}\left(m_ra^2 + m_fx_f^2\right)-\color{green}{U\frac{J_{yyf}}{R_{fw}}\cos \lambda} \right)\\ +& \dot{\psi}\left(\color{red}{U\left(m_fx_f + m_r a\right)}\right)\\ =& \color{blue}{F_f b} \end{aligned} \end{equation}
Because steering and yaw are directly coupled through the equation $\dot{\psi} = \frac{U\sin\lambda}{b}\delta + \frac{c\sin \lambda}{b}\dot{\delta}$ (See this notebook for derivation), the steer and yaw directions are not energetically independent. They are, however, coupled through the constraint that the tires roll without slip on the road surface. This means that the tire forces are "constraint forces" in the "non-holonomic" (in terms of velocity only) roll-without-slip constraints. In the language of LaGrangian mechanics, we have an "ignorable coordinate." Rather than implying that the coordinate is not important, this means that one of the two coupled, non-independent generalized coordinates (yaw, in our case) can be eliminated algebraically.
As we can see in Eqns 23 and 24, the unknown front tire lateral force $F_f$ appears in both, and is not multiplied by any of our generalized coordinates or their derivatives. The strategy will be to solve Eqn 24 for $F_f$ and substitute it into Eqn 24 to eliminate the need for Eqn 24 altogether. Solving Eqn 24 for $F_f$ yields:
\begin{equation} \begin{aligned} \color{blue}{F_f}=&\\ &\ddot{\phi}\left( -\frac{1}{b}\left(m_rah_r+m_fx_fh_f\right) \right)\\ +& \ddot{\delta} \left(\frac{c\sin\lambda}{b^2}\left(m_ra^2+m_fx_f^2\right) + \frac{1}{b}m_fx_f u \right)\\ +& \dot{\phi} \color{green}{\left(\frac{U}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)\right)}\\ +& \dot{\delta} \left( \frac{U\sin\lambda}{b^2}\left(m_ra^2 + m_fx_f^2\right)-\color{green}{\frac{U}{b}\frac{J_{yyf}}{R_{fw}}\cos \lambda} \right)\\ +& \dot{\psi}\left(\color{red}{\frac{U}{b}\left(m_fx_f + m_r a\right)}\right)\\ \end{aligned} \end{equation}
Now that we have an expression for $F_f$, we can substitute this into Eqn 23, eliminating the unknown constraint force and capturing the yaw dynamics in our equation for the steer dynamics.
\begin{equation} \require{cancel} \begin{aligned} &\ddot{\phi} \left( -m_f u h_f -\frac{c\sin \lambda}{b}\left(m_rah_r+m_fx_fh_f\right)\right) \\ +& \ddot{\delta} \left( m_f\left(u^2 + \frac{c\sin \lambda}{b} x_f u\right) + \frac{c^2\sin^2\lambda}{b^2}\left(m_ra^2+m_fx_f^2\right) + \frac{c\sin\lambda}{b}m_fx_f u \right) \\ +& \dot{\phi} \color{green}{\left(\frac{Uc\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)+U\sin\lambda\frac{J_{yyf}}{R_{frw}}\right)} \\ +& \dot{\delta} \left(m_f x_f u \frac{U\sin \lambda}{b} +\frac{Uc\sin^2\lambda}{b^2}\left(m_ra^2 + m_fx_f^2\right)+\color{green}{\cancel{\frac{Uc\sin\lambda\cos\lambda}{b}\frac{J_{yyf}}{R_{fw}}}-\cancel{\frac{Uc\sin\lambda\cos\lambda}{b}\frac{J_{yyf}}{R_{fw}}}}\right) \\ +& \dot{\psi}\left(\color{red}{m_f u U } + \color{red}{\frac{Uc\sin\lambda}{b}\left(m_fx_f + m_r a\right)}\right)\\ +& \phi \left(m_f g u + \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}}\right) \\ +& \delta \left(-m_f g u - \color{blue}{\frac{gc\sin\lambda\cos \lambda \left(m_ra+m_fx_f\right)}{b}} \right) \\ =& T_{in,\delta} \end{aligned} \end{equation}
Notice that the two $\dot{\delta}\frac{Uc\sin\lambda\cos\lambda}{b}\frac{J_{yyf}}{R_{fw}}$ terms canceled each other out-- one was from the gyroscopic torque equation in the yaw direction, and the other was from gyroscopic torque in the steer direction.
The last substitution we need to make is to eliminate yaw rate entirely. Luckily, we know that Because steering and yaw are directly coupled through the equation $\dot{\psi} = \frac{U\sin\lambda}{b}\delta + \frac{c\sin \lambda}{b}\dot{\delta}$ (See this notebook for derivation). Making this substitution and re-grouping terms multiplied by $\delta$ and $\dot{\delta}$ gives us our final equation for the $\delta$-direction.
\begin{equation} \begin{aligned} &\ddot{\phi}& \left( -m_f u h_f -\frac{c\sin \lambda}{b}\left(m_rah_r+m_fx_fh_f\right)\right) \\ +& \ddot{\delta}& \left( m_f\left(u^2 + 2\frac{c\sin \lambda}{b} x_f u\right) + \frac{c^2\sin^2\lambda}{b^2}\left(m_ra^2+m_fx_f^2\right) \right) \\ +& \dot{\phi}& \color{green}{\left(\frac{Uc\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)+U\sin\lambda\frac{J_{yyf}}{R_{frw}}\right)}\\ +& \dot{\delta}& \left(m_f x_f u \frac{U\sin \lambda}{b} +\frac{Uc\sin^2\lambda}{b^2}\left(m_ra^2 + m_fx_f^2\right) \right.\\ &&+\left. \color{red}{\frac{Uc\sin\lambda}{b}m_f u + \frac{Uc^2\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)}\right) \\ +& \phi& \left(m_f g u + \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}}\right) \\ +& \delta& \left(-m_f g u - \color{blue}{\frac{gc\sin\lambda\cos \lambda \left(m_ra+m_fx_f\right)}{b}} \right.\\ &&+\left. \color{red}{\frac{U^2\sin\lambda}{b}m_f u + \frac{U^2c\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)} \right. \\ &&+\left. \color{green}{\frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b}} \right) \\ =& T_{in,\delta} \end{aligned} \end{equation}
We can also make that same substitution to eliminate $\psi$ and its derivatives from the $\phi$-equation, Eqn 22.
\begin{equation} \begin{aligned} &\ddot{\phi} \left( m_rh_r^2 + m_fh_f^2 \right)\\ +& \ddot{\delta}\left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right)\\ +& \dot{\delta}\left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right) \right. \\ & \left. - \color{red}{ \frac{Uc\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ & \left. - \color{green}{U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) - U\frac{J_{yyf}}{R_{fw}}\sin\lambda}\right)\\ +& \phi \left(-m_r g h_r - m_f g h_f\right) \\ +& \delta \left(m_f g u + \color{blue}{ \frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)} \right. \\ & \left. - \color{red}{ \frac{U^2\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ & \left. -\color{green}{ \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)}\right)\\ =& T_{in,\phi} \end{aligned} \end{equation}
Our two second-order equations of motion are Eqn 28 (for $\phi$) and Eqn 27 (for $\delta$). Equation 28 is reproduced below for easy reference:
\begin{equation*} \begin{aligned} &\ddot{\phi} \left( m_rh_r^2 + m_fh_f^2 \right)\\ +& \ddot{\delta}\left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right)\\ +& \dot{\delta}\left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right) \right. \\ & \left. - \color{red}{ \frac{Uc\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ & \left. - \color{green}{U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) - U\frac{J_{yyf}}{R_{fw}}\sin\lambda}\right)\\ +& \phi \left(-m_r g h_r - m_f g h_f\right) \\ +& \delta \left(m_f g u + \color{blue}{ \frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)} \right. \\ & \left. - \color{red}{ \frac{U^2\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ & \left. -\color{green}{ \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)}\right)\\ =& T_{in,\phi} \end{aligned} \end{equation*} And Equation 27 is reproduced below for easy reference. \begin{equation*} \begin{aligned} &\ddot{\phi}& \left( -m_f u h_f -\frac{c\sin \lambda}{b}\left(m_rah_r+m_fx_fh_f\right)\right) \\ +& \ddot{\delta}& \left( m_f\left(u^2 + 2\frac{c\sin \lambda}{b} x_f u\right) + \frac{c^2\sin^2\lambda}{b^2}\left(m_ra^2+m_fx_f^2\right) \right) \\ +& \dot{\phi}& \color{green}{\left(\frac{Uc\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)+U\sin\lambda\frac{J_{yyf}}{R_{frw}}\right)}\\ +& \dot{\delta}& \left(m_f x_f u \frac{U\sin \lambda}{b} +\frac{Uc\sin^2\lambda}{b^2}\left(m_ra^2 + m_fx_f^2\right) \right.\\ &&+\left. \color{red}{\frac{Uc\sin\lambda}{b}m_f u + \frac{Uc^2\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)}\right) \\ +& \phi& \left(m_f g u + \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}}\right) \\ +& \delta& \left(-m_f g u - \color{blue}{\frac{gc\sin\lambda\cos \lambda \left(m_ra+m_fx_f\right)}{b}} \right.\\ &&+\left. \color{red}{\frac{U^2\sin\lambda}{b}m_f u + \frac{U^2c\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)} \right. \\ &&+\left. \color{green}{\frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b}} \right) \\ =& T_{in,\delta} \end{aligned} \end{equation*}
It is convenient to represent these equations in a matrix version of the "mass-spring-damper" second order equation, called "MDK" form. Compactly, we can write:
\begin{equation} M\vec{\ddot{q}} + D \vec{\dot{q}} + K \vec{q} = \vec{F}\vec{u} \end{equation}
In our case, after eliminating $\psi$, we have $\vec{q} = \left[\phi,\delta \right]^T$. Because we have already collected terms in both the roll and steer equations of motion, we can express the model compactly as:
\begin{equation} \begin{bmatrix}M11 & M12 \\M21 & M22 \end{bmatrix}\begin{bmatrix}\ddot{\phi} \\ \ddot{\delta} \end{bmatrix} + \begin{bmatrix}D11 & D12 \\D21 & D22 \end{bmatrix}\begin{bmatrix}\dot{\phi} \\ \dot{\delta} \end{bmatrix} + \begin{bmatrix}K11 & K12 \\K21 & K22 \end{bmatrix}\begin{bmatrix}{\phi} \\ {\delta} \end{bmatrix} = \begin{bmatrix}T_{in,\phi} \\ T_{in, \delta}\end{bmatrix} \end{equation}
Unpacking Eqns 24 and 28, we can find the coefficients in the $M,D,K$ matrices:
\begin{equation} \begin{aligned} M11 &=& \left( m_rh_r^2 + m_fh_f^2 \right) \\ M12 &=& \left(-m_fh_fu-\frac{c\sin\lambda}{b}\left(m_fx_fh_f+m_rh_ra\right) \right) \\ M21 &=& \left( -m_f u h_f -\frac{c\sin \lambda}{b}\left(m_rah_r+m_fx_fh_f\right)\right) \\ M22 &=& \left( m_f\left(u^2 + 2\frac{c\sin \lambda}{b} x_f u\right) + \frac{c^2\sin^2\lambda}{b^2}\left(m_ra^2+m_fx_f^2\right) \right) \\ D11 &=& 0 \\ D12 &=& \left( \frac{U\sin\lambda}{b}\left(-m_rah_r-m_fx_fh_f\right) \right. \\ && \left. - \color{red}{ \frac{Uc\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ && \left. - \color{green}{U\frac{c\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right) - U\frac{J_{yyf}}{R_{fw}}\sin\lambda}\right) \\ D21 &=& \color{green}{\left(\frac{Uc\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)+U\sin\lambda\frac{J_{yyf}}{R_{frw}}\right)}\\ D22 &=&\left(m_f x_f u \frac{U\sin \lambda}{b} +\frac{Uc\sin^2\lambda}{b^2}\left(m_ra^2 + m_fx_f^2\right) \right.\\ &&+\left. \color{red}{\frac{Uc\sin\lambda}{b}m_f u + \frac{Uc^2\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)}\right) \\ K11 &=& \left(-m_r g h_r - m_f g h_f\right) \\ K12 &=& \left(m_f g u + \color{blue}{ \frac{gc\sin \lambda}{b}\left(m_f x_f + m_r a\right)} \right. \\ && \left. - \color{red}{ \frac{U^2\sin \lambda}{b}\left(m_f h_f + m_r h_r\right)} \right. \\ && \left. -\color{green}{ \frac{U^2\sin\lambda}{b}\left(\frac{J_{yyf}}{R_{fw}}+\frac{J_{yyr}}{R_{rw}} \right)}\right)\\ K21 &=& \left(m_f g u + \color{blue}{\frac{gc\sin\lambda \left(m_ra+m_fx_f\right)}{b}}\right) \\ K22 &=& \left(m_f g u - \color{blue}{\frac{gc\sin\lambda\cos \lambda \left(m_ra+m_fx_f\right)}{b}} \right.\\ &&+\left. \color{red}{\frac{U^2\sin\lambda}{b}m_f u + \frac{U^2c\sin^2\lambda}{b^2}\left(m_fx_f + m_r a\right)} \right. \\ &&+\left. \color{green}{\frac{J_{yyf}}{R_{fw}}\frac{U^2\sin\lambda\cos\lambda}{b}} \right) \end{aligned} \end{equation}
Finally the Forcing matrix $F$ is simply the identity matrix in our system.
Putting the equations of motion in MDK form allows us to see what physical parameters and processes are responsible for "mass-like," "damper-like," and "spring-like" behavior in our system. We can also see the coupling between the generalized coordinates, roll and steer, in this form, by looking at the off-diagonal terms in each matrix. For example, we can see that tire forces and D'Alembert forces provide "spring-like" coupling from roll motion to steer motion by looking at the term K12.
What we can't see as easily using MDK form is whether the model is stable at a particular forward speed or for a particular parameter set. We also can't easily design a feedback controller to stabilize or improve the performance of the bike when the model is in MDK form. To easily find the model's eigenvalues and put it in a form that's suitable for control design, we can use a little bit of matrix math to transform our MDK form into State Space Form.
The MDK form of the model we developed in Section 1.11 is probably the most compact and natural form of the model, especially when using Lagrange's method to derive it. However, it is relatively easy to transform the model into state space form if we pick the state vector $\vec{x} = \begin{bmatrix}\phi & \delta & \dot{\phi} & \dot{\delta} \end{bmatrix}^T$. This state vector makes sense since potential energy is stored in the generalized coordinates, and kinetic energy is stored in their derivatives. The state vector is 4th order, as we'd expect given the independent energy storage processes in our model. Our goal in this section will be to transform the model into the standard state space form, written as:
\begin{equation} \dot{\vec{x}} = A\vec{x} + B\vec{u} \end{equation}
The state vector we chose is special, because we can write it as $\vec{x} = \begin{bmatrix}\vec{q} & \dot{\vec{q}} \end{bmatrix}^T$. This makes finding the state derivative equations for the first two states very easy! It means we just have to find the state derivatives for the second states, or $\frac{d}{dt}\dot{\vec{q}}=\ddot{\vec{q}}$.
beginning with the standard MDK form of Eqn 30, $M\vec{\ddot{q}} + D \vec{\dot{q}} + K \vec{q} = \vec{F}\vec{u}$, we can simply pre-multiply all terms by $M^{-1}$ and move all terms except $\ddot{\vec{q}}$ to the right-hand side of the equation.
\begin{equation} \ddot{\vec{q}} = -M^{-1}D\dot{\vec{q}} - M^{-1}K\vec{q} + M^{-1}F\vec{u} \end{equation}
This equation will become the "bottom half" of our state space $A$ and $B$ matrices. We can write our equations in state space form as:
\begin{equation} \underbrace{\frac{d}{dt} \begin{bmatrix} \phi \\ \delta \\ \dot{\phi} \\ \dot{\delta} \end{bmatrix}}_{\dot{\vec{x}}} = \underbrace{\begin{bmatrix} \textbf{0}_{2x2} & \textbf{I}_{2x2} \\ - M^{-1}K & - M^{-1}D \end{bmatrix}}_{A} \underbrace{\begin{bmatrix} \phi \\ \delta \\ \dot{\phi} \\ \dot{\delta} \end{bmatrix}}_{\vec{x}} + \underbrace{\begin{bmatrix}\textbf{0}_{2x1} \\ M^{-1}F \end{bmatrix}}_{B}\underbrace{\begin{bmatrix} T_{in,\phi} \\ T_{ind,\delta} \end{bmatrix}}_{\vec{u}} \end{equation}
While it would be messy to write the model in this form symbolically, especially given the complexity of the mass matrix in MDK form, it is easy enough to build the model in code using MDK form and simply transform it in order to simulate it, find its eigenvalues, or design a controller for the model.
To simulate how the bike would respond to a step torque on the handlebars, we can build the model in MDK form, transform it into state space form, and then simulate it using the "step()" function. To begin, we reference Eqn 32 for a particular parameter set. we will use the parameter values for the Lafayette College self-driving Razor minibike, and write a function that builds a state-space model for the bike for a particular forward speed U.
from numpy import *
from matplotlib.pyplot import *
from scipy import signal
import control
def getModelMDK (U,printmodel=False):
a = .3386#meters, distance from rear axle to CG in x direction
b = .767#meters, wheelbase of bike
c = .023#.08#meters, trail
hrf = .25606#meters, rear frame CG height
mrf = 11.065#kg, rear frame mass inc. rider
xff = .62218#position of front frame CG
yff = 0#y-position of the front frame CG
zff = .46531#height of the front frame CG
mff = 2.2047 #kg, fork mass
Rfw = .15875 #m, radius of the front wheel
mfw = 1.486 #kg, wheel mass
Rrw = 0.15875 # radius of real wheel
mrw = 2.462 #mass of rear wheel
mr = mrw+mrf #mass of rear frame includes rear wheel
hr = (mrf*hrf+mrw*Rrw)/(mr) #CG height of rear frame includes rear wheel
Jyyf = 0.020502342#mfw*Rfw**2
Jyyr = 0.033968214#mrw*Rrw**2
Sf = Jyyf/Rfw
Sr = Jyyr/Rrw
St = Sf+Sr
mf = mff+mfw #total mass of front frame includes front wheel
xf = (mff*xff+b*mfw)/mf# total front frame x position including front wheel
hf = (zff*mff+Rfw*mfw)/mf #total front frame mass height including front wheel
lam = 1.16 #radians, angle from negative x axis to steering axis
g = 9.81 #m/s/s, graUitational constant
u = hf*cos(lam)-(b+c-xf)*sin(lam) #perpendicular distance from steer axis to front frame CG (positive if CG in front of steer axis)
#build terms for the MDK model based on Eqn32
M11 = mr*hr**2 + mf*hf**2
M12 = -mf*hf*u- c*sin(lam)/b*(mf*xf*hf+mr*hr*a)
M21 = -mf*hf*u- c*sin(lam)/b*(mf*xf*hf+mr*hr*a)
M22 = mf*(u**2+2*c*sin(lam)/b*xf*u)+c**2*sin(lam)**2/b**2*(mr*a**2+mf*xf**2)
D11 = 0
D12 = U*sin(lam)/b*(-mr*hr*a - mf*xf*hf)-U*c*sin(lam)/b*(mf*hf+mr*hr)-U*c*sin(lam)/b*(Jyyf/Rfw+Jyyr/Rrw)-U*Jyyf/Rfw*sin(lam)
D21 = U*c*sin(lam)/b*(Jyyf/Rfw+Jyyr/Rrw)+Jyyf/Rfw*U*sin(lam)
D22 = U*sin(lam)/b*mf*xf*u + U*c*sin(lam)**2/b**2*(mr*a**2+mf*xf**2)+U*c*sin(lam)/b*mf*u+U*c**2*sin(lam)**2/b**2*(mf*xf+mr*a)
K11 = -(mr*g*hr+mf*g*hf)
K12 = mf*g*u+g*c*sin(lam)/b*(mf*xf+mr*a)-U**2*sin(lam)/b*(mf*hf+mr*hr)-U**2*sin(lam)/b*(Jyyf/Rfw+Jyyr/Rrw)
K21 = mf*g*u + g*c*sin(lam)/b*(mr*a+mf*xf)
K22 = -mf*g*u-g*c*sin(lam)*cos(lam)/b*(mr*a+mf*xf) + U**2*sin(lam)/b*mf*u+U**2*c*sin(lam)**2/b**2*(mf*xf+mr*a) + Jyyf/Rfw*U**2*sin(lam)*cos(lam)/b
M = array([[M11, M12],[M21, M22]])
D = array([[D11, D12],[D21, D22]])
K = array([[K11, K12],[K21, K22]])
return M,D,K,eye(2)
def getModelSS(v):
#first get the model in MDK form
M,D,K,F = getModelMDK(v)
A = hstack((zeros((2,2)),eye(2,2)))#first create the 'top half' of A matrix
A = vstack((A,hstack((dot(-linalg.inv(M),K),dot(-linalg.inv(M),D)))))# now fill in bottom half
B = vstack((zeros((2,2)),dot(linalg.inv(M),F)))#now stack zeros on top of our M^-1F term
C = array([[1,0,0,0],[0,1,0,0]]) #choose the 'outputs' as just roll and steer
D = zeros((2,2)) #with two possible inputs, two possible outputs, there are four terms in the D matrix when output eqn is y = Cx+Du
sys = control.StateSpace(A,B,C,D)
return sys
To actually simulate the bike's behavior, we will check the eigenvalues to see if the bike is stable at the speed we want. If it is, we can use the "lsim" function to run a step response.
#pick a velocity
velocity = 4 #m/s
#get the state space model
sys = getModelSS(velocity)
#check the eigenvalues. All real parts must be <0 for stability.
eigs,vecs = linalg.eig(sys.A)
print("Eigenvalues at "+str(velocity)+" m/s are:")
print(eigs)
As we can see, the bike is self-stable (for hands-free riding) at this speed. We can find the model's step response to a 0.1 N-m torque at the handlebar using the 'step_response' function in python's 'control' library.
tsim,yout = control.step_response(sys)
#scale yout by the input magnitude (0.1), convert to degrees
yout = yout*.1*180/pi
#yout has shape (num_outputs,num_inputs,num_timesteps)
#we only want to see steer torque->roll angle and steer torque->steer angle, so only need 2nd input's response.
figure()
subplot(2,1,1)
plot(tsim,yout[0][1][:],'k')
ylabel('roll angle (deg)')
title('Model response to a 0.1 Nm step steer torque')
subplot(2,1,2)
plot(tsim,yout[1][1][:],'k')
ylabel('steer angle (deg)')
xlabel('time (s)')
A two-wheeler like a bicycle or motorcycle is capable of self-stabilization (hands-free riding) but only at some speeds. To understand how the self-stabilization of the bike functions (or doesn't) at different speeds, we can look at the real and imaginary parts of the state space model's eigenvalues. Looping through different speeds and plotting the real and imaginary parts of the model's eigenvalues can show us stable and unstable speeds. Where all of the eigenvalues' real parts are negative, the bike is stable without rider inputs. Looking at the imaginary parts of the eigenvalues at a particular speed can tell us how oscillatory the bike is at a particular speed. The larger the magnitude of the imaginary parts, the more oscillatory the bike is.
#create a vector of velocities to investigate
vvec = arange(.01,10,.01)
#create a second copy of this vector that is four rows. This will make plotting easier
vvec2 = zeros((4,len(vvec)))
#our model is fourth order, so will have 4 eigenvalues. each can have a real and/or imaginary part.
eigs_re = zeros((4,len(vvec)))
eigs_im = zeros((4,len(vvec)))
for k in range(0,len(vvec)):
#get current velocity
v = vvec[k]
#get state space model at this speed
sys= getModelSS(v)
#get eigenvalues at this speed
eigs,vecs = linalg.eig(sys.A)
#get real parts and place in proper matrix for storage
eigs_re[:,k] = real(eigs)
#get imaginary parts and place in proper matrix for storage
eigs_im[:,k] = imag(eigs)
#fill up velocity vector corresponding with each eigenvalue
vvec2[:,k] = [v,v,v,v]
#creat a figure for us to plot the eigenvalues.
figure()
plot(vvec,eigs_re[0,:],'k.',vvec,eigs_im[0,:],'k')
xlabel('Speed (m/s)')
ylabel('Eig (1/s)')
legend(['Real Part','Imaginary part'])
plot(vvec,eigs_re[1,:],'k.',vvec,abs(eigs_im[1,:]),'k')
plot(vvec,eigs_re[2,:],'k.',vvec,abs(eigs_im[2,:]),'k')
plot(vvec,eigs_re[3,:],'k.',vvec,abs(eigs_im[3,:]),'k')
#limit our view so we can see what's happening
axis([0,10,-30,30])