Abstract

Professional drivers in drifting competitions demonstrate accurate control over a car's position and sideslip while operating in an open-loop unstable region of state-space. Could similar approaches help autonomous cars contend with excursions past the stable handling limits, thereby improving overall safety outcomes? As a first step toward answering that question, this paper presents a novel controller framework for automated drifting along a path. The controller is derived for the general case, without reference to a nearby equilibrium point. This leads to the physically insightful result that one can use the rotation rate of the vehicle's velocity vector to track the path, while simultaneously using the yaw acceleration to stabilize sideslip. Nonlinear model inversion, in concert with low-level wheelspeed control, is then used to achieve these required state derivatives over a broad range of conditions. Experiments on MARTY, a modified 1981 DMC DeLorean, demonstrate excellent tracking of a path with varying curvature, speed, and sideslip. Comparisons to a test run without wheelspeed control highlight the importance of accounting for the rear saturated-tire wheelspeed dynamics.

1 Introduction

Exceeding a vehicle's handling limits can lead to strong input coupling and instability—conditions that overwhelm traditional control architectures with independent lateral/longitudinal control and that explicitly assume open-loop stable sideslip dynamics. Yet, drivers in “drifting” competitions routinely operate in this region of state-space, while achieving precise control over both sideslip and the vehicle's path. Developing controllers for automated drifting could provide great insight into the general problem of fully utilizing the entire state-space and ensuring that the widest possible range of maneuvers is available to an autonomous vehicle, should the need arise. This could be particularly relevant when navigating inclement weather or difficult terrain: work by Acosta et al. [1], for example, suggests that driver assistance systems that can access these regimes greatly outperform traditional stability control on gravel surfaces. The ability to harness these coupled dynamics could also help mitigate cases of excessive limit understeer.

Early examples in the literature demonstrated stabilization of the vehicle states about a single drift equilibrium, both in simulation, by Velenis et al. [2], and experiment, by Hindiyeh et al. [3]. Because the typical set of inputs—steering, drive torque, and brakes—renders the problem underactuated, adding on the objective of tracking a desired path is not straightforward. Recently, several works have experimentally demonstrated some form of this combined task for simple, constant-curvature circles: the approach by Werling et al. [4] tracked sideslip and vehicle course, while that by Goh and Gerdes [5] tracked sideslip and a specified path. However, due to restrictive assumptions in vehicle modeling or controller formulation, these approaches cannot be easily extended to more complex trajectories.

Indeed, these examples, as well as other studies of the drifting phenomenon, have used a large range of vehicle models. Two-state single-track models were used early on by Ono et al. [6] and Voser et al. [7] to discuss the unstable dynamics of drifting. Hindiyeh et al. [3] and Goh and Gerdes [5] both used three-state single-track models with forces as direct inputs to formulate their controllers, while Werling et al. [4] explicitly included steering and throttle delay. And in Ref. [2], a four-wheel model with weight transfer and wheelspeed/differential dynamics was linearized about a single drift equilibrium for a linear quadratic regulator. In general, the appropriate level of model fidelity—and consequently, choice of control inputs—is an open question.

Contrasting with the previous approaches, this paper develops and experimentally demonstrates a controller structure for automated drifting that is designed explicitly to handle complex trajectories. Vehicle sideslip and lateral error from a curvilinear path coordinate system are chosen as objectives, and the desired controller dynamics are first derived without assuming a specific vehicle dynamics model, or that the vehicle is near an equilibrium point.

This results in a physically insightful control law expressed in terms of the vehicle's state derivatives. When drifting, a standard assumption is removed—the orientation of the vehicle's velocity vector no longer follows that of the vehicle body. Although this at first seems daunting, the controller derivation instead reveals an opportunity: the rotation rate of the vehicle's velocity vector can now be used directly to track the path. Then, by yawing the vehicle body faster or slower than its velocity vector, we can simultaneously control the sideslip of the vehicle.

To realize this controller, we need a vehicle model that strikes a balance between the various levels of fidelity, yet captures the essential physical phenomena. A condition that distinguishes drifting from normal driving is that the rear tires are continuously fully saturated. Indeed, this is generally an important limiting condition to understand, but is a quick transient event in most aggressive driving situations; sustained drifting allows us to explore this at length.

Analyzing the implications of these saturated-tire dynamics motivates the use of an inner wheelspeed control loop to exploit the force–slip relationship. This then enables the treatment of the rear tire forces as direct inputs in the nonlinear model inversion of a three-state single-track model in the outer loop. This physically motivated, cascaded approach allows us to accurately achieve the controller's required state derivatives over the broad range of conditions encountered in a general trajectory.

Experiments on the full-scale MARTY test vehicle (Fig. 1) confirm the effectiveness of the controller in tracking a path with curvature that varies from 1/7 to 1∕20 m, while speed ranges from 25 to 45 km/h, and sideslip is held at −40 deg. Comparisons to a test run without the inner wheelspeed control loop then lend empirical insight to the importance of accounting for the rear wheelspeed dynamics.

Fig. 1
MARTY during an automated drifting test
Fig. 1
MARTY during an automated drifting test
Close modal

2 Vehicle Modeling

In this section, we first introduce the equations of motion for the force-based single-track model in a curvilinear coordinate system; the tire force models are then described.

2.1 Equations of Motion.

2.1.1 Path-Tracking States and Dynamics.

The vehicle, shown schematically in Fig. 2, has three states. The total velocity vector, with magnitude V, is pointed at a sideslip angle β from the vehicle's longitudinal axis. The yaw rate of the vehicle's body is then denoted as r.

Fig. 2
Three-state single-track model with reference path
Fig. 2
Three-state single-track model with reference path
Close modal
To incorporate path tracking, we introduce several additional states. First, we define the vehicle course, ϕ, as the direction of the vehicle's velocity vector measured to some globally fixed inertial frame χ. The vehicle's CG moves in the direction of ϕ. Importantly, ϕ˙ is thus the rotation rate of the velocity vector (often also known as the course rate), and is kinematically linked to both sideslip and yaw rate
(1)

The position of the vehicle is tracked using a curvilinear coordinate system relative to the reference path, as commonly used throughout the literature. The lateral error e is the distance between the vehicle CG and the point on the reference path closest to it; s is the distance along the reference path to this point. Together, they locate the vehicle relative to the reference path, as shown in Fig. 2.

We use the subscript ref to denote reference quantities at s along the reference path. The reference course ϕref is the tangent angle of the reference path, and the course error, Δϕ=ϕϕref, is the angular deviation between the vehicle course and the reference course.

The dynamics of e are then
(2)
(3)

where we have used a few simplifying assumptions: sinΔϕΔϕ and VΔϕ˙V˙Δϕ. This is a reasonable assumption as Δϕ is driven small in closed-loop operation.

Finally, the dynamics of Δϕ˙ are
(4)

where κref is the curvature of the reference path.

2.1.2 Vehicle States and Dynamics.

The nonlinear model inversion is conducted using the single-track “bicycle” model as shown in Fig. 2. The forces acting on the vehicle are the front lateral force Fyf, the rear lateral force Fyr, and the rear longitudinal force Fxr. The equations of motion are then
(5)

where δ is the steering angle, a and b are the distance from the CG to the front and rear axles, respectively, and m is the mass of the vehicle.

2.2 Front Tire Force Modeling.

The front lateral force Fyf is modeled using the Fiala brush tire model [8], which was also used by the drifting controllers described in Refs. [3] and [5]
(6)

where Fz is the normal load on the tire, Cα is the cornering stiffness, α is the slip angle, and μ is the coefficient of friction.

2.3 Rear Tire Force Modeling.

When drifting, the entire rear tire contact patch is in a fully sliding condition. Assuming an isotropic friction value, the tire force is then given directly by the “friction circle” relationship
(7)

3 Controller Development

3.1 Overview.

The task of the controller is to track the specified path and sideslip using steering δ and rear drivetrain torque τ as inputs. This motivates choosing the lateral error e and sideslip β as the control objectives.

The overall structure of the controller is shown in Fig. 3. In the first part, desired stable dynamics are imposed on e and β simultaneously. This yields a desired course rate ϕ˙des, as well as rsyn, a synthetic yaw rate input to the sideslip dynamics. Closing the loop around rsyn then yields a desired yaw acceleration, r˙des.

Fig. 3
Block diagram of overall controller structure
Fig. 3
Block diagram of overall controller structure
Close modal

In the next step of the controller, the nonlinear vehicle dynamics model (5) is inverted to transform the pair of desired state derivatives, ϕ˙des and r˙des, into a steering angle δ and a desired thrust angle γdes. The thrust angle is then mapped to a desired wheelspeed, ωdes. Finally, the loop is closed around ωdes to produce a torque command τ.

3.2 Imposed Error Dynamics

3.2.1 Path Tracking.

The path of the vehicle is tracked using the rotation rate of the vehicle's velocity vector, ϕ˙. First, stable second-order dynamics are imposed on the lateral error e
(8)
Adding the reference course rate (4) yields the desired value ϕ˙des
(9)

3.2.2 Sideslip Stabilization.

Noting the kinematic relation (1), β˙=ϕ˙r, and with ϕ˙ set by the above path-tracking requirement, we see immediately that yaw rate, relative to the vehicle course rate, can be used as a synthetic input to track sideslip.

This is similar to the approaches in Refs. [3] and [5], except that, rather than assuming a steady-state approximation for ϕ˙rref, we are using the desired ϕ˙des instead.

Sideslip is stabilized by imposing first-order dynamics on the sideslip tracking error eβ=ββref
(10)
The synthetic yaw rate required to achieve these dynamics, rsyn, is then computed by substituting ϕ˙des and β˙des in Eq. (1)
(11)
An inner loop is then closed around rsyn by imposing the first-order dynamics on the synthetic yaw rate tracking error, er=rrsyn, yielding the desired r˙des
(12)
where r˙syn is the derivative of the synthetic yaw rate, and based on our desired dynamics, can be approximated as
(13)

where we have again assumed V˙0 and Δϕ small. As expected, r˙des=r˙ref when the errors are zero. Although we include the first terms in parenthesis in Eq. (13) for completeness, it is worth noting that they are typically quite small compared to the other terms in r˙des.

3.3 Nonlinear Model Inversion and Velocity Dynamics.

The force-based nonlinear single-track model, described in Eqs. (5)(7), is numerically inverted to map the desired pair of state derivatives (ϕ˙des,r˙des) to a steering angle δ and a rear thrust angle γ. Because there are two desired state derivatives and two inputs, the total acceleration V˙ is an uncontrolled variable that is set by the choice of (ϕ˙des,r˙des). Thus, the speed of the vehicle is not explicitly regulated. However, the coupling between the lateral and the longitudinal dynamics that occurs at high sideslip stabilizes velocity when operating under the imposed control law.

Noting that our controller explicitly drives e,Δϕ,er,andeβ to 0, we can develop an intuition for the stability of V by analyzing it as a corresponding zero-dynamic. At this condition, we have that
(14)

This linear dependence of ϕ˙des on V suggests that velocity should be stable as long as V˙ϕ˙<0 and V˙ has a zero-crossing along r˙=r˙ref, or more generally, along contours of constant r˙. This is determined by the shape of the surface of possible state derivatives, a representative example of which is shown in Fig. 4.

Fig. 4
Representative example of feasible surface of possible state derivatives for the MARTY vehicle model at the state r = 0.94 rad/s, V = 9.35 m/s, and β=−40 deg
Fig. 4
Representative example of feasible surface of possible state derivatives for the MARTY vehicle model at the state r = 0.94 rad/s, V = 9.35 m/s, and β=−40 deg
Close modal
Figure 5 shows ϕ˙ plotted against V˙ for contours of constant r˙. Assuming only that these contours are in general concave, then the separatrix above which V˙ϕ˙<0 can be defined as
(15)
Fig. 5
ϕ˙ versus V˙ along contours of constant r˙
Fig. 5
ϕ˙ versus V˙ along contours of constant r˙
Close modal

As long as this separatrix lies below the plane V˙=0, constraining our model inversion to this “upper” surface should have stable velocity zero-dynamics. This also has the benefit of making the mapping of (ϕ˙des,r˙des) one-to-one, simplifying the model inversion (Fig. 6).

Fig. 6
r˙ versus ϕ˙, with V˙ contours
Fig. 6
r˙ versus ϕ˙, with V˙ contours
Close modal

Since the shape of the feasible surface changes with the state, this argument is only useful if these conditions are generally true over a broad range of states. Numerically checking this over the large range 0.2<r<1.25rad/s,3<V<30m/s,and5<β<50deg, and plotting the resultant state-space volume in Fig. 7, we see that this is indeed valid except for very high yaw rates at very low speeds.

Fig. 7
Volume of state-space with separatrix below the V˙=0 plane
Fig. 7
Volume of state-space with separatrix below the V˙=0 plane
Close modal

This idea of leveraging—rather than fighting—the coupled velocity dynamics leads to an interesting analogical takeaway: when operating in this open-loop unstable region, there is a shuffling of objectives. When driving normally, steering is used to track a path and throttle to regulate speed, and the yaw dynamics yield a stable sideslip response; while drifting, steering, and throttle are used in coordination to track a path and sideslip, and the coupling between the state dynamics yields a stable velocity response.

3.3.1 Projection into Feasible Space.

For a general trajectory, it is possible for the commanded (ϕ˙des,r˙des) pair to fall outside the feasible actuation space. For this initial presentation and testing of the controller structure, we elect to handle these cases in a naive way. The value of ϕ˙des computed in Eq. (9) is saturated to fall within the feasible values of ϕ˙, before being used in Eq. (11) to compute r˙des. The resultant (ϕ˙des,r˙des) pair is then simply projected into the feasible space along the r˙=r˙des line. This strategy roughly prioritizes the unstable yaw/sideslip dynamics over the lateral error dynamics.

4 Wheelspeed Dynamics and Control

The friction circle relationship (7) has been used in Refs. [3] and [5] to formulate controllers that map a desired rear lateral force Fyr to a rear longitudinal force Fxr, which is then treated directly as an input to the system by multiplying through the tire radius to yield a rear axle torque command
(16)

This simple mapping assumes that wheelspeed dynamics can be ignored and is supported by experimental validation of their controllers. However, other approaches in the literature have not made the same assumption, leaving the question of its importance as an open one. For example, in Ref. [2], Velenis et al. use wheelspeed as one of the inputs of a LQR controller for a system linearized about a single drift equilibrium. The wheelspeed is related to tire force with the Pajecka coupled-slip model [9], and a backstepping controller closes the loop around wheelspeed using the total rear axle torque. The controller is successfully simulated using carsim software.

In this paper, we hope to directly address this question through both theoretical discussions below and experimental comparisons in Sec. 5.

4.1 Saturated-Tire Force–Slip Relationship.

The forces from the rear tire arise from the slip between the tire contact patch and the road. For a fully saturated tire, this relationship can be modeled in a way that is both simple and physically insightful: the magnitude of the force is μFzr and its direction opposes the slip velocity vector Vslip of the contact patch. Defining this direction as the thrust angle γ, and referring to Fig. 8, it can be immediately seen that changing the length of the Rω vector directly rotates γ. Geometrically, this relationship is
(17)

where R is the radius of the tire, ω is the wheelspeed, and Vtravel,xr and Vtravel,yr refer to the longitudinal and lateral components of the vehicle velocity at the tire, respectively.

Fig. 8
Velocity and force vectors for the sliding rear tire
Fig. 8
Velocity and force vectors for the sliding rear tire
Close modal

It is important to note that this relationship agrees with both the brush [10]2 and the simplified Pajecka magic formula tire models [9] at full saturation.

The control input to the system, τ, finally appears in the model of ω dynamics
(18)

where Iω is the rotational inertia of the wheel-tire-drivetrain system, and τ is the applied torque.

4.2 Proposed Advantages of Wheelspeed Control.

Rather than simply mapping a desired rear lateral/longitudinal force to torque, as in Eq. (16), a low-level controller could instead use torque to regulate wheelspeed to values desired by the force–slip relationship (17). This approach offers several potential advantages.

First, it provides increased robustness to variations in μFzr. An intuitive way to see this is shown graphically in Fig. 9: holding a constant Fxr yields large changes in Fyr for variations in μFzr, compared to holding a constant γ, which yields smaller changes in both Fyr and Fxr. This can also be analyzed quantitatively in the partial derivatives of the tire forces with respect to μFzr in the two cases of constant Fxr and constant γ
(19)
Fig. 9
Graphical illustration of increased sensitivity of Fyr to μFzr when controlling Fxr versus controlling γ
Fig. 9
Graphical illustration of increased sensitivity of Fyr to μFzr when controlling Fxr versus controlling γ
Close modal

These are plotted against γ in Fig. 10, where it is clearly seen that Fyr(μFzr)|Fxr grows large relative to the other sensitivities when |γ|0.75rad.

Fig. 10
Comparison of partial derivatives of Fyr and Fxr with respect to μFzr, given constant Fxr or constant γ
Fig. 10
Comparison of partial derivatives of Fyr and Fxr with respect to μFzr, given constant Fxr or constant γ
Close modal

Second, these wheelspin dynamics lead to appreciable delays in force generation. With Eqs. (18) and (17) and the parameters for the MARTY test vehicle shown in Table 1, selected time responses for Fxr generation for a step torque input around a typical drift equilibrium at V=9.5m/s,r=0.79rad/s,andβ=40deg are shown in Fig. 11. Also plotted is the aggregate 95% rise time over the range of Fxr=0.050.95μFzr. We see that not only does the rise time vary by almost an order of magnitude in this range but that the values are quite high throughout. A useful point of comparison is the lateral force rise time for the nonsliding front tires that comes about from the tire relaxation length phenomenon. At the same speed, and using a typical estimate for tire relaxation length of σR=0.33 m [11], we expect a front lateral force 95% rise time of (σ/V)log(0.05)=0.10s. From Fig. 11, we see that the force rise time for the rear sliding tires around the equilibrium force value Fxr=0.72μFzr is more than five times this value. This large delay relative to front lateral force generation is particularly important for the controller design presented here, which dictates coordinated steering and rear longitudinal/lateral force inputs over a broad range of conditions. Using a low-level controller to regulate wheelspeed would allow us to set the closed-loop force rise time at a value small enough that the forces can be considered as direct inputs to the system, as in Eq. (5). This cascaded approach preserves the tractability and intuition of dealing with the force-based equations, while explicitly accounting for the delays arising from wheelspeed dynamics.

Fig. 11
Selected time responses and aggregate 95% rise time for Fxr with wheelspeed dynamics around a drift equilibrium
Fig. 11
Selected time responses and aggregate 95% rise time for Fxr with wheelspeed dynamics around a drift equilibrium
Close modal
Table 1

Vehicle and controller parameters

ParameterSymbolValue
Massm1700 kg
Rotational inertiaIz2385kgm2
CG to front axlea1.392 m
CG to rear axleb1.008 m
Track widthd1.60 m
CG heighth0.45 m
Rear weight transfer proportionPr0.75
Tire radiusR0.33 m
Single wheel + drivetrain inertiaIω3kg m2
Max steering angleδmax38 deg
Yaw rate gainkr6
Sideslip gainkβ2
Path-tracking proportional gainkp2
Path-tracking derivative gainkd2.8
ParameterSymbolValue
Massm1700 kg
Rotational inertiaIz2385kgm2
CG to front axlea1.392 m
CG to rear axleb1.008 m
Track widthd1.60 m
CG heighth0.45 m
Rear weight transfer proportionPr0.75
Tire radiusR0.33 m
Single wheel + drivetrain inertiaIω3kg m2
Max steering angleδmax38 deg
Yaw rate gainkr6
Sideslip gainkβ2
Path-tracking proportional gainkp2
Path-tracking derivative gainkd2.8

4.3 Wheelspeed Control Implementation.

The nonlinear model inversion step described in Sec. 3.3 yields a rear longitudinal force/thrust angle command, which can be mapped through the force–slip relationship (17) to a desired wheelspeed. This ωdes is in turn achieved with acceptable bandwidth using a simple form that draws inspiration from dynamic surface control by Swaroop et al. [12]
(20)

where ωdes,f is the desired wheelspeed after a first-order filter with time constant tω, and we have used the desired rear longitudinal force Fxrdes to compute the feedforward torque.

Because the MARTY test vehicle has independently powered rear wheels that are mechanically decoupled, for experimental testing, we have to use a separate control loop for each wheel. Setting γdes,RL=γdes,RR=γdes yields the target rear-left and rear-right wheelspeeds ωdes,RL=ωdesdr/(2R) and ωdes,RR=ωdes+dr/(2R), where d is the vehicle track width. The feedforward rear longitudinal force for each wheel is computed by making a rough steady-state approximation for weight transfer
(21)

where Pr is the proportion of lateral weight transfer that occurs over the rear axle and h is the CG height.

5 Experimental Validation

Experiments on the MARTY testbed showcase the effectiveness of the controller for a reference path with speeds between 25 and 45 km/h, curvature between 1/7 and 1/20 m, and sideslip of up to –40 deg.

5.1 Test Vehicle.

MARTY, depicted in Fig. 1, is a modified 1981 DMC DeLorean that has been equipped with computer-controlled electric power steering and two electric motors that drive the left-rear and right-rear wheels independently. Vehicle parameters used in the experiment are shown in Table 1. An Oxford Technical Systems RT4003 dual-antenna integrated RTK-GPS/IMU is used to obtain vehicle state information at 250 Hz. The controller is implemented on a dSpace MicroAutoBoxII (DS1401) computer that also runs at 250 Hz, and interfaces with the steering, throttle, and navigation subsystems.

5.2 Reference Path Generation.

While the controller is derived for a general drifting path, in the interest of convenience and succinctness, we use an existing simple path generation procedure—namely, the “quasi-equilibrium” strategy proposed in Ref. [5].

The path is composed of a sequence of unstable drifting equilibrium points. First, a desired curvature κref and sideslip βref profile as a function of path distance s is selected. Then, for each point on the path, the equations of motion (5) are solved given the conditions β=βref,ϕ˙=κrefV,andV˙=r˙=0, yielding the reference path values of ϕ˙refandVref.

The selected profile (Fig. 12) has curvature between 1/7 and 1/20 m, with reference sideslip of up to 40deg and results in equilibrium speeds between 25 and 45 km/h. The resultant path is shown in black in Fig. 13.

Fig. 12
Selected curvature and sideslip profile versus distance along path
Fig. 12
Selected curvature and sideslip profile versus distance along path
Close modal
Fig. 13
Measured versus reference path for experimental run
Fig. 13
Measured versus reference path for experimental run
Close modal

5.3 Test Procedure.

Simple entry and exit clothoids are appended to the start and end of the desired path, and a basic path-tracking controller, similar to that presented by Kritayakirana and Gerdes [13], is used to guide the vehicle on this path. The drifting controller is activated at s =57m and de-activated at s =463 m. The controller and vehicle parameters are shown in Table 1.

5.4 Results for Controller With Wheelspeed Control.

The controller with wheelspeed control tracks the reference path well, as manifested in good lateral error and sideslip tracking performance. A video of an experimental run with this controller can be found online.3

The measured path of the vehicle is shown in blue in Fig. 13 and adheres very closely to the reference path (black). Indeed, from the lateral error plotted in Fig. 14, we see that the largest deviation is just –0.36 m; the root-mean-square (RMS) lateral error is 0.18 m.

Fig. 14
Path-tracking performance during the experimental run
Fig. 14
Path-tracking performance during the experimental run
Close modal

This path-tracking performance is even more impressive when considering that the vehicle is operating around its large target sideslip of 40deg, as seen in Fig. 15. This target value is large compared to the maximum steering range of ±38deg and puts the vehicle close to the limits of actuation. The biggest deviation in sideslip tracking is 6.1deg, and the RMS sideslip tracking error is 2.4deg. The measured yaw rate tracks the synthetic yaw rate quite well, except during the initial transition to a drifting condition. It is interesting to note that velocity stays quite close to the quasi-equilibrium values. This suggests that the closed-loop velocity dynamics are indeed stable, which is expected since the states never leave the volume (Fig. 7) wherein we hypothesize this to be true. Additionally, it indicates that the model and parameters used for path planning have quite accurately predicted the equilibrium values.

Fig. 15
States versus path distance during the experimental run
Fig. 15
States versus path distance during the experimental run
Close modal

Steering and rear thrust angle commands are shown in Fig. 16. This trajectory exercises the nonlinear model inversion over a broad range of states, resulting in a similarly wide range of inputs—this is most clearly exemplified by 65deg of steering angle the controller sweeps through during the test. Finally, it is useful to confirm the assumption used in deriving the equations of motion for lateral error in Eq. (3): referring to Fig. 17, we see that experimentally, VΔϕ˙ is everywhere much larger than V˙Δϕ.

Fig. 16
Steering and thrust angle commands during the experimental run
Fig. 16
Steering and thrust angle commands during the experimental run
Close modal
Fig. 17
Comparison of contributions to e¨ from VΔϕ˙ and V˙Δϕ
Fig. 17
Comparison of contributions to e¨ from VΔϕ˙ and V˙Δϕ
Close modal

5.5 Comparison to Controller Without Wheelspeed Control.

To investigate the impact of the cascaded wheelspeed control structure proposed in Sec. 4.2, we compare these results to a test run with wheelspeed control de-activated. In this case, the commanded total rear axle torque is simply τcommand=RFxrdes as in Eq. (16). Because the left and right wheels are independently controlled and mechanically decoupled, a simple low-level proportional controller is used to “lock” their wheelspeeds together by changing the torque distribution between the left and right wheels; this is akin to a closed-loop version of the feedforward torque distribution used in Ref. [5] for autonomous drifting around a single equilibrium.

The states of the vehicle are plotted in red in Fig. 18, with the previous results shown in blue. Although sideslip is generally stabilized around the reference, we see that there are significant oscillations in both sideslip and yaw rate. This behavior is also seen in the path-tracking performance, shown in red in Fig. 19. Although the reference path is generally tracked, both lateral error and course error are far larger and more oscillatory than the case with wheelspeed control shown in blue. Furthermore, we see very large, high-frequency corrections in both steering angle and rear thrust angle, plotted in red in Fig. 20.

Fig. 18
Comparison of states versus path distance for test runs with wheelspeed control (blue) and without (red)
Fig. 18
Comparison of states versus path distance for test runs with wheelspeed control (blue) and without (red)
Close modal
Fig. 19
Comparison of path-tracking performance for test runs with wheelspeed control (blue) and without (red)
Fig. 19
Comparison of path-tracking performance for test runs with wheelspeed control (blue) and without (red)
Close modal
Fig. 20
Comparison of steering and thrust angle commands versus path distance for test runs with wheelspeed control (blue) and without (red)
Fig. 20
Comparison of steering and thrust angle commands versus path distance for test runs with wheelspeed control (blue) and without (red)
Close modal

One candidate explanation for this behavior, as discussed in Sec. 4.2, is delay between the desired rear forces and the actual rear forces due to wheelspeed dynamics. With three states and three forces (5), it is straightforward to numerically differentiate the measured signals, invert the equations of motion, and obtain measured values of the forces.

A Lissajous-style plot of the measured Fyr and Fxr against their desired values is shown in Fig. 21. Results for the experiment without wheelspeed control (red) show large looping orbits, indicating a significant amount of phase lag. This effect is especially stark when viewed against the results with wheelspeed control (blue), which fall very close to the ideal 1:1 line (black) over the entire test.

Fig. 21
Lissajous-style plots of Fyr and Fxr versus their commanded values for both experimental runs
Fig. 21
Lissajous-style plots of Fyr and Fxr versus their commanded values for both experimental runs
Close modal

6 Conclusion

This paper derives a physically insightful controller for autonomous drifting along a general path that is formulated in terms of the vehicle's state derivatives. The rotation of the vehicle's velocity vector is used to track the lateral error in a curvilinear coordinate system. Then, sideslip is simultaneously stabilized by yawing the vehicle body relative to this velocity vector.

The required state derivatives are then mapped to actuator inputs using nonlinear model inversion cascaded with a simple wheelspeed control loop. An examination of the dynamics of the saturated rear tires suggests that this approach provides advantages in terms of control bandwidth and robustness to disturbances, compared to assuming longitudinal force is a direct input.

This choice of lateral error and sideslip as objectives is made all the more interesting by the concomitant relegation of velocity to an uncontrolled variable. By analyzing the zero-dynamics of velocity in this controller framework, we draw an interesting analogical takeaway. When driving within the stability limits, steering is used to track the path and throttle to regulate speed, and the yaw dynamics naturally yield a stable sideslip response. When drifting, however, steering and throttle are used in coordination to track a path and sideslip, and the coupling between the state dynamics yields a stable velocity response.

Experimental results for a quasi-equilibrium trajectory with curvature between 1/7 and 1/20 m, speeds between 25 and 45 km/h, and sideslip of up to 40deg demonstrate accurate tracking of both sideslip and lateral error. Furthermore, comparing these results to a test run without wheelspeed control highlights the effectiveness of the cascaded approach. This points to an interesting area of exploration for stability control systems on the individual tire level: rather than preventing saturation all together, wheel slip could instead be used to control the thrust angle from a sliding tire, leading to novel capabilities.

The theme of expanding the envelope of operation extends to the more general vehicle level as well. The ability to harness—rather than shy away from—these coupled dynamics could greatly assist in certain cases, including those of excessive limit understeer and driving on loose surfaces. The current approaches to trajectory planning often constrain themselves to regions with open-loop stable yaw dynamics, or stricter still, due to either modeling assumptions or unsuitable behavior by the vehicle and underlying controller. This controller was derived with a relatively simple force-based model not unlike those presently used by some planning architectures. As such, it could quickly enable future research on trajectory planning—beyond the “quasi-equilibrium” approximation presented here—that works in concert with the chassis control layer to confidently venture outside these regions and more fully utilize the state-space.

Footnotes

2

The brush model is described in many places, but the authors find this description of saturated tire dynamics by Svendenius to be particularly comprehensive.

Acknowledgment

The authors wish to thank the Revs Program at Stanford, Bridgestone Corporation, Brembo Corporation, and Renovo Motors for supporting this work, as well as our Dynamic Design Lab colleagues for assisting during testing at Thunderhill Raceway Park. The authors also specially thank the late Professor J. Karl Hedrick for his mentorship in life in general, and in vehicle dynamics, dynamic surface control, and zero-dynamics in particular.

References

1.
Acosta
,
M.
,
Kanarachos
,
S.
, and
Fitzpatrick
,
M. E.
,
2017
, “
A Hybrid Hierarchical Rally Driver Model for Autonomous Vehicle Agile Maneuvering on Loose Surfaces
,”
14th International Conference on Informatics in Control, Automation and Robotics
, Vol.
2
, ICINCO, INSTICC, SciTePress, Madrid, Spain, July 26–28, pp.
216
225
.
2.
Velenis
,
E.
,
Katzourakis
,
D.
,
Frazzoli
,
E.
,
Tsiotras
,
P.
, and
Happee
,
R.
,
2011
, “
Steady-State Drifting Stabilization of RWD Vehicles
,”
Control Eng. Pract.
,
19
(
11
), pp.
1363
1376
.10.1016/j.conengprac.2011.07.010
3.
Hindiyeh
,
R. Y.
, and
Gerdes
,
J. C.
,
2014
, “
A Controller Framework for Autonomous Drifting: Design, Stability, and Experimental Validation
,”
ASME J. Dyn. Syst. Meas. Control
,
136
(
5
), p.
051015
.10.1115/1.4027471
4.
Werling
,
M.
,
Reinisch
,
P.
, and
Gröll
,
L.
,
2015
, “
Robust Power-Slide Control for a Production Vehicle
,”
Int. J. Veh. Auton. Syst.
,
13
(
1
), pp.
27
42
.10.1504/IJVAS.2015.070727
5.
Goh
,
J. Y.
, and
Gerdes
,
J. C.
,
2016
, “
Simultaneous Stabilization and Tracking of Basic Automobile Drifting Trajectories
,” IEEE Intelligent Vehicles Symposium (
IV
), Gothenburg, Sweden, June 19–22, pp.
597
602
.10.1109/IVS.2016.7535448
6.
Ono
,
E.
,
Hosoe
,
S.
,
Tuan
,
H.
, and
Doi
,
S.
,
1998
, “
Bifurcation in Vehicle Dynamics and Robust Front Wheel Steering Control
,”
IEEE Trans. Control Syst. Technol.
,
6
(
3
), pp.
412
420
.10.1109/87.668041
7.
Voser
,
C.
,
Hindiyeh
,
R. Y.
, and
Gerdes
,
J. C.
,
2010
, “
Analysis and Control of High Sideslip Manoeuvres
,”
Veh. Syst. Dyn.
,
48
(
Supp. 1
), pp.
317
336
.10.1080/00423111003746140
8.
Fiala
,
E.
,
1954
,
Seitenkrafte Am Rollenden Luftreifen
, Vol.
96
,
Verein Deutscher Ingenieur
,
Berlin
, pp.
973
979
.
9.
Bakker
,
E.
,
Nyborg
,
L.
, and
Pacejka
,
H. B.
,
1987
, “
Tyre Modelling for Use in Vehicle Dynamics Studies
,”
SAE
Paper No. 870421.10.4271/870421
10.
Svendenius
,
J.
,
2007
, “
Tire Modeling and Friction Estimation
,” Ph.D. thesis,
Department of Automatic Control, Lund University
,
Lund, Sweden
.
11.
Pacejka
,
H. B.
,
2006
,
Tire and Vehicle Dynamics
,
SAE International, Warrandale, PA
.
12.
Swaroop
,
D.
,
Hedrick
,
J. K.
,
Yip
,
P. P.
, and
Gerdes
,
J. C.
,
2000
, “
Dynamic Surface Control for a Class of Nonlinear Systems
,”
IEEE Trans. Autom. Control
,
45
(
10
), pp.
1893
1899
.10.1109/TAC.2000.880994
13.
Kritayakirana
,
K.
, and
Gerdes
,
J. C.
,
2012
, “
Autonomous Vehicle Control at the Limits of Handling
,”
Int. J. Veh. Auton. Syst.
,
10
(
4
), pp.
271
296
.10.1504/IJVAS.2012.051270