Abstract

This paper presents a novel approach for path-following control of a four-wheeled autonomous vehicle. The rear wheels of the vehicle are driven independently, all four wheels can be braked independently, and the front wheels are steered together. The proposed cascade structure consists of two convex optimization-based parts: one for path-following and another for the control allocation problem of the actuators. The control algorithm presents cost functions for the allocation problem focusing on safety. The proposed cost functions were examined and compared to former ones in a simulation environment. After all, the controller was tested in real-time test on a Lotus Evora test vehicle developed by ThyssenKrupp.

1. Introduction

Driving assistant systems and autonomous driving are aiming to increase safety on roads. If human-driven cars are replaced with autonomous vehicles, accidents caused by human errors can be eliminated [1]. All vehicles on the roads can have the driving ability of a tireless driving instructor or car racer. When all actuators are coordinated by one main system, even higher performance can be reached because the human drivers cannot request directly differential torque or braking on the wheels. This system includes redundancy: in some cases, when an error appears on the actuators or one actuator reaches its limits, another actuator can be activated to reach the target as it is presented in [2] for differential steering that can be used as a backup.

The robot control problem is often separated into two parts. The first is to plan the global path, including path planning from the starting point to the endpoint and avoiding obstacles [3]. Its task is to recognize the traffic situation and make decisions, such as whether it is safe or not to perform a lane change [4]. The second problem is to make the robot follow the desired path despite internal and external disturbances by controlling its actuators. This paper focuses on the second one: path-following and longitudinal speed tracking.

The lateral control methods for autonomous ground vehicles with the modeling considerations are gathered in [5], including linear and nonlinear approaches. The linear parameter-varying (LPV) methods can be effectively used for handling nonlinearities indirectly in a polytopic form [6]. However, these methods include complex weighting functions and scheduled gains. The lateral and the longitudinal control are handled separately in [7], where the LPV method is expanded with the control for handling uncertainties. The goal of the controller is determined based on generalized forces summed up using weighting factors. A linear matrix inequality- (LMI-) based fuzzy controller is created for the lateral control [8, 9], considering the physical limitations of the vehicle and possible lateral disturbances successfully. The longitudinal speed is handled as a time-varying parameter in this approach, not as a control input.

The lateral-longitudinal control problem is usually solved with the data-driven method, which is a general approach for lateral and longitudinal control that effectively handles the changes of external parameters [10]. This type of controller can also solve the problem of both front and rear wheel steering [11]. However, it is not a standard solution among civil vehicles, so the presented benefits are not widely applicable. This method does not take into account the fact that several vehicle models can be considered during the controller construction because they provide insight into the relationships between the internal states of the vehicle.

Another common solution is the model predictive controller (MPC) that uses the vehicle model to solve the problem. One type is the tube-based MPC, handling the model uncertainties based on the linear vehicle model [12]. A hybrid incremental MPC using a simplified dual neural network for separated longitudinal and lateral control is presented in [13]; however, there are a lot of parameters and weights to be tuned intuitively for its proper performance. Hierarchical controllers were introduced using the details of the model to provide resistance against parameter changes. A tube-based MPC guarantees robustness with hierarchical architecture: the upper level of the controller uses a nominal model of the vehicle system to realize state feedback [14].

It is also important to handle the physical limitations of the system. A hierarchical structure is created with a sliding mode controller in the upper level responsible for handling the limitations of the actuator [15]. A reference model with the steady-state approach prescribes the desired states for the lower part, where two solutions are presented and compared: a dynamic load-based and an optimization-based control rule. A multiconstraint approach of a nonlinear MPC can handle input saturation, where an autoregressive neural network supports the yaw stabilization of the controller [16]. The performance of MPC-based methods is tuned experimentally by weighting matrices based on rules and cost functions that are created intuitively, merging different physical phenomena. These algorithms are computation-intensive concerning real-time applications. Sometimes global optimization is used for these methods that can find only local minima. A constrained MPC controller maximizes the tire stability margin with yaw moment control [17]. However, due to the number of parameters, the robustness of the MPC is needed to be improved. A model inversion-based solution can handle parameter variations also, besides the physical limitations [18]. However, the proposed method uses global optimization.

In most cases, lateral and longitudinal behaviors are handled separately. A linear parameter-varying and flatness-based design for separated lateral and longitudinal control can deal with a nonlinear model [19]. The controllers are then combined in a hierarchical structure. Another approach uses the interaction between the longitudinal and the lateral acceleration, evaluated with limitations on a diagram (so-called G-G diagram) [20]. The limitations can be handled in a different way, using envelope constraints in the phase plane (sideslip angle-sideslip rate or sideslip angle-yaw rate) [21]. Yaw rate or yaw motion also can form the basis of a lateral controller concerning the stability of the motion of the vehicle [22]. A sliding mode control-based approach with an online adjusted control law handles parameter uncertainties and system nonlinearities [23]. A hierarchical controller deals with the lateral and longitudinal control problem with prioritizing lateral control [24]. The tire force-based approach creates a piecewise control for longitudinal speed that requires a complex tuning method for smooth transitions. An integrated lateral and longitudinal controller can be more effective in high dynamics situations than the combination of two separated controllers.

The paper presents, reflecting on the critical points highlighted above, a convex optimization-based control algorithm using physical parameters in the control rules with the following contributions. A hierarchical cascade structure is developed with internal model control (IMC), using the four-wheel nonlinear model of the vehicle to provide robustness. The outer part of the proposed structure consists of an optimization-based path-following controller, based on prediction horizon with a novel approach minimizing the control effort while interpreting references (position and orientation) as a limitation. The advantage of this approach is that there are no weights in the cost function, so the optimization does not depend on further parameters. The inner part of the structure is responsible for the allocation problem of determining the control request values for all five actuators. This paper presents an optimization-based solution for the allocation problem, with cost functions focusing on safety behavior by minimizing extremum values, considering system limitations (input saturation, etc.). The cost functions aim to minimize quantities with physical significance (dissipation and power), so a minimal number of tuning parameters are needed. The optimization problems were transformed into a convex form to be solved in a real-time environment, so the presented architecture was tested in an autonomous vehicle using online optimization.

The rest of the paper is structured as follows. In Section 2, two different vehicle models are presented with the nonlinear tire model used in the controller. The proposed cascade controller structure is presented in Section 3. Section 4 details the outer loop of the controller with the optimization. It is followed by Section 5 that describes the internal model control-based inner loop for actuator control with optimization for the control allocation problem. In Section 6, the simulation results are presented, evaluating the cost functions for the control allocation problem. After that, Section 7 presents the real-time measurement results of a Lotus Evora test vehicle. Finally, in Section 8, the conclusions are gathered.

2. Modeling Considerations

Firstly, the modeling considerations for the vehicle are presented: the kinematic and the two-track dynamic model. After that, the wheel and tire models are detailed, which are used in the dynamic model. These models are suitable to illustrate the complexity of the presented problem and are used in the control algorithm, presented in Sections 4 and 5.

2.1. Kinematic Model

The basic approach for modeling the motion of a robot car is the kinematic approach, which is the simplest method (dynamic effects are omitted). So, many assumptions, detailed later, should be considered when using it. The behavior of the vehicle can be calculated from the internal states, the yaw rate , and speed [5]:where , and denote the position and the orientation of the vehicle, respectively.

This point mass model includes the nonholonomic constraints of the vehicle when describing its movement. This model is ideal to describe the lateral behavior of the vehicle with the yaw rate when only its lateral movement is considered (the outer loop of the proposed cascade structure), independently from the actuator level. The actuator level control (steering wheel and independently actuated wheels) is delegated to a lower level, determining how to reach the desired yaw rate.

2.2. Dynamic Two-Track Model

The two-track model should be used to handle the four wheels of the vehicle independently when considering high dynamics behavior. This model can be seen in Figure 1. For the tire forces calculation, the lateral and the longitudinal speeds have to be calculated in local frames [5].where is the angle of the front wheels, is the lateral speed of the vehicle, and are the fronts and rear wheelbases, and and are the distance between the center of gravity (COG) and the front or rear axle, respectively. The dynamic equations can be gained by writing up the force and moment balance for the COG of the vehicle [25]:

The steering system of the vehicle contains an electrical power control unit that can be modeled with a rate limit followed by a first-order element. The dynamic behavior of the steering system can be described as follows:where is the actual value of front wheel angle, is the control value, and is the time constant of the first-order element. The rate limiter has two parameters: maximum steepness and maximal final value limit .

2.3. Tire Modeling

The nonlinear tire model was used for the proposed controller. In this model, the lateral forces are originated from lateral slip [26].

The first character of the lower index denotes the position of the wheel lengthwise (front (f) or rear (r)) and the second broadwise (left (l) or right (r)). According to [27], the nonlinear tire model can be approximated with trigonometric functions:where denotes the tire-road friction coefficient, denotes the shape factor, is the stiffness factor, and is the vertical force. As it can be seen, this model is simple to describe, so it is easy to calculate. At the same time, it carries the main nonlinear attributes of the tire, approximating its natural behavior correctly. The vertical force is calculated from the physical configuration of the vehicle, affected by the forces generated by longitudinal acceleration [26]:where is the distance between COG and the front, is the distance between the COG and the back of the vehicle, and is the COG-ground distance.

Supposing that the friction coefficient and the requested longitudinal acceleration will not exceed certain limits and considering that the inertia of the tire is negligible compared to the inertia of the vehicle, longitudinal forces can be calculated directly from the tire torques [7]:where denotes the wheel torque and is the effective radius of the wheel. The parameter values of the vehicle used in the simulation and measurements can be found in Table 1.

3. Outlook of Control Structures

The cascade structure of the proposed control method can be seen in Figure 2 with the two nested loops.

The outer loop consists of an optimization-based reference generation that uses the kinematic model for the local path planning. The inputs of this part are the actual state variables of the vehicle (yaw rate, speed vector, position, and orientation), and it generates a reference of yaw rate derivative and longitudinal velocity derivative for the inner loop.

The inner loop solves the control allocation problem of the underdetermined system, and it is also responsible for the robustness of the control algorithm. The online optimization determines the requested torques and steering angle from the input reference signal received from the outer loop, minimizing physical quantities. The robustness against parameter changes, external disturbances, and resistance to system noises is ensured by the internal model control (IMC) structure of the internal loop.

Physical limitations of the system should be considered at each level as it is presented for steering limitations in [3]. In both loops, the limitations of the vehicle (steering rate and final value, torque rate and final value, etc.) were considered by design. The controller runs with both in the simulation and real-time measurements: the actual states are gained from measurements, and the optimization-based calculation defines the control request. In each control period, both the reference generator and the inner loop are evaluated.

4. The Outer Loop for Reference Generation

The outer loop of the cascade controller is of a prediction-based structure. With the prediction, the proposed algorithm depicts the human driver’s behavior who wants to eliminate the error on a previewed section of the reference. At this stage, the lateral and the longitudinal behavior is handled separately, having different lengths of sections.

It is an effective way to handle lateral behavior based on yaw rate or yaw moment [28]. The time window for the yaw rate-based lateral control defines the interval for a local maneuver to implement path tracking. In each control period, based on the actual states of the vehicle (yaw rate, speed, position, and orientation) and the predefined path, a localization algorithm calculates the states to be reached at the end of the time window. First, it seeks the closest point on the path; then based on the orientation and actual speed, supposing that the actual speed persists for the time window, it calculates the required lateral displacement. The controller can calculate the desired orientation and yaw rate from the reference path given for the time window. Concerning the reference path, there is one requirement: it should be feasible considering the limitations of the vehicle (nonholonomic and dynamic constraints).

4.1. Lateral Reference

The results of the localization and the actual states together create a final value problem to be solved. In this approach, the path is a constraint for the given time window, and the only question is how the yaw rate trajectory is defined to fulfill these. The lateral reference tracking problem is solved using the kinematic model of the vehicle, presented in Subsection 2.1. To ensure the stability of the vehicle, this part of the controller considers the physical limitations of the system.

When solving the problem, the given time window is separated into equal slices, and the local trajectory of the vehicle is calculated using linear approximations. The yaw rate forms the basis of the calculation, and each slice is described with only one parameter, its steepness, denoted by . The sliced trajectory approximation can be seen in Figure 3. The actual yaw rate of the slice can be calculated using linear approximation:where , is the initial yaw rate, and is the length of the slice .

The orientation of the vehicle at the end of the slice can be calculated from the linearized yaw rate:

As soon as the local trajectory is generated via optimization, the expressions of (1) have to be linearized for the lateral displacement calculation to gain a convex problem. The small-angle assumptions can be used for calculating the lateral displacement at the end of the time window [29]. Using equation (11), it can be calculated in a closed form:

Equations (10)–(12) determine the equality constraints of the optimization. Although the lateral movement is calculated using the kinematic model, dynamic restrictions can be considered by knowing that the derivative of the yaw rate is affected by limitations of inertia and the transfer characteristics of each actuator. Also, this limitation is needed to ensure that the linearization would not result in invalid reference planning.

The cost function of the optimization determines the control rule for the lateral behavior. The minimal control effort was set to be a target to gain stability, which means that the energy spent on changing the yaw rate is minimized:

This cost function carries a physical meaning and contains no weights to be tuned intuitively during the tests.

Finally, the optimization problem was formulated:where

The first lines in matrices and correspond to orientation, the second to the position, and the third to yaw rate, derived from equations (10)–(12). is the limit of the derived yaw rate. The problem is convex, giving a unique minimum point, and can be solved, for example, by the lsqlin solver of MATLAB, using the active-set algorithm. The time spent on the solution is small enough to be integrated into a real-time solution.

It is supposed that the reference path is determined to be feasible by this optimization method. Suppose any disturbance or error occurs so that the presented optimization problem becomes infeasible. In that case, the algorithm tries to solve the problem with the following modifications: the time window is expanded in a fixed number of steps (considering the computation capacity of the system) so that the controller can seek for longer path, finding back to the reference. If the problem is still infeasible, the vehicle performs an emergency stop.

Some aspects have to be considered when setting the reference generation parameter . With the increase of , the path-following performance can be improved. However, the improvement is not growing as intensively as its computation demand. A good tradeoff can be set, considering the capabilities of the real-time environment.

4.2. Longitudinal Reference

The longitudinal reference generation works separately from the lateral one. It may have a different length time window (denoted by ), concerning that the lateral dynamics have different properties than longitudinal dynamics. The acceleration reference is calculated using the actual speed , the desired speed , and the length of the time window:

The minimal value for is the sampling time of the control loop, and it is the best solution theoretically concerning the signal tracking performance. Since a real vehicle configuration has to be handled with its low-level actuators, the limitations and latencies of the system should be considered. Knowing the maximal control input and the maximal possible latency, can be set to suppress all the negative effects of the low-level system. Finding the minimal value that fulfills this criterion leads to a minimal performance decrease in reference tracking introduced by .

This section presented the outer loop that is responsible for lateral and longitudinal reference tracking.

5. IMC-Based Force-Allocation Control

The inner loop of the proposed structure can be seen in Figure 4. The structure formulates the internal model control (IMC) scheme: the two-track model presented in Section 2 is connected parallel to the vehicle, and the inverse of the model is implemented to calculate the control signals. The inverse-based calculation of the control distribution can be performed based on predefined rules or optimization. The optimization-based methods have more degrees of freedom in designing [30], so this method was used in the presented work to include more effective safety and stability issues. The optimization task will be detailed later. The whole structure is built around two physical characteristics of the model equations (3): the longitudinal force and the yaw moment .

The model with its inverse provides the transfer function of unity in the steady state. On the feedback branch, the difference between the states of the model and the vehicle is calculated and filtered by autoregressive-like filters. This feedback guarantees the robustness of the system. The output of the vehicle, the longitudinal acceleration, is available as raw data, and the derivative of the yaw rate is calculated by numerical approximation [19]. The feedback is filtered by low-pass filters responsible for suppressing noise and uncertainties of numerical calculations performed on the raw data.

5.1. Optimization Problem

The distribution block in Figure 4 calculates the inverse of the model via optimization, solving the allocation problem of the underdetermined system.

The two-track model with the tire model presented in Section 2 has to be simplified to gain convex constraints for the distribution, which provides the required moment and force. It is known that the front wheel steering has a rate limit, so it restricts the interval that can be reached on the lateral tire force characteristics. The equations of the two-track model can be linearized around the actual road-wheel angle without introducing significant error into the system. The linearization is calculated by evaluating the expression of the tire force and its derivative at the initial point. When the equations of the two-track model are linearized around the actual state, further nonlinear expressions are formed by two coefficients to be handled on the front wheels: both the steering angle and the torque determine the tire forces. These expressions were further simplified by substituting one coefficient (which depends on torque) with its measured value, supposing to be constant, compared to the other coefficient, as soon as their slope is an order of magnitude smaller than the slope of the other coefficient (which depends on the steering angle). The equations of the locally linearized two-track model can be transformed into a matrix form, which creates the basis for the inverse calculation for the IMC loop.

Finally, the control allocation problem is dedicated to solving the inverse of the model to satisfy the requested force and , by minimizing a cost function , using the control vector :

The cost function is convex. Later, different proposed cost functions are examined in detail in Subsection 5.2. The control inputs have rate limits and final value limits determined by the configuration of the vehicle: for the maximum value of the steering angle, for the steering rate, for the maximum value of the torque, and for the rate of the torque. There were limitations added to the lateral tire forces in the first inequality constraint to prevent tire saturation. Also, knowing that the vertical force is transformed to lateral forces, it should be guaranteed by the second inequality constraint that the tire forces will stay inside the friction circle [20]. These limitations are responsible for the vehicle and inner variables’ dynamics stability in the inner loop. It should be noted that the driven-braked and the braked-only wheels only differ in that the front wheels can have only negative torques. The feasibility of the presented optimization problem is guaranteed by the outer loop since its output, which serves as an input for this part, is generated considering the physical limitations (rate limits and final value limits) of the model. This way, the inverse calculation always has a solution.

The presented task is a second-order cone programming (SOCP) convex optimization problem. The mathematical details of this kind of problem are widely discussed in literature [31]. This problem can be solved, for example, with MATLAB coneprog solver. The solver uses the interior-point method algorithm. Maximum time can be set for the solver to guarantee an anytime result, so its computational burden does not exceed the capability of the real-time application resources.

5.2. Cost Functions

For the control allocation problem, there are several solutions used for driver assistant systems. The main two directions for the optimization are the dissipation-based and the force-based methods that are presented in [32] and [33], respectively. The force-based approach calculates the tire workload by normalizing to the vertical force resulting from the lateral and longitudinal forces as shown in [25]. The dissipation-based method is also used in [34] and calculates the tire dissipation rate from the measured speed and the tire forces: , where is the longitudinal slip speed: with , the rotational speed of the wheel.

It is common to use quadratic functions when calculating these expressions for the whole vehicle, summing up for the four wheels, as it is presented in [33, 32, 25]. The quadratic functions used in the literature are calculated for the two approaches:

It is common to use the norm in measuring dissipation performance, and norm fits the best to the physical meaning of the force-based approach. The quadratic summation of the four wheels leads to a unique solution in the optimization. However, it is hard to find the physical meaning of this expression. Nonquadratic summation of the dissipation or the normalized force would lead to sets of optimal solutions without any highlighted solution. There would be another optimization needed to choose one from this set.

In this paper, two cost functions are introduced to maximize the reserve in each wheel to improve safety. The min–max approach focuses on the worst-case scenario by minimizing the probability of slipping any of the wheels. The maximum workload usage using the norm for the force and the maximum dissipation rate using the norm for the force and the speed are proposed to be minimized:

5.3. Control Method Summary

In the last three sections, the proposed cascade control algorithm is presented. To have a comprehensive insight, the control algorithm that is calculated in each control period is illustrated in Figure 5.

An optimization-based reference planner is used in the outer loop to solve the local path-following problem, requiring the state variables leading to the minimal control effort by the inner loop. This optimization uses the kinematic vehicle model and sets the path as a constraint with final value restrictions in orientation and position, imitating the strategy of the human driver. The further state variables of the vehicle (vehicle sideslip, lateral speed, etc.) are determined implicitly by this cost function, so there is no need for further components to be included in the cost function. This way, no intuitive weights (concerning position, orientation, and other vehicle variables) are used, which is a great advantage compared to usual MPC solutions.

The inner loop is also optimization-based and realizes the IMC structure for the control distribution problem. This structure provides robustness for the system concerning model mismatch, external disturbances, and parameter changes. This part uses the two-track vehicle model, including the nonlinear tire model for the parallel model of the IMC loop and the optimization-based inverse calculation. There are two proposed cost functions for the inverse calculation. Both are physical phenomenon-based, excluding weights by the minimax approach for the worst-case calculation. The dissipation rate is calculated using the L1 norm and the tire force using the L2 norm. Overall the main advantages of the proposed structure are that the tuning parameters are minimized by introducing physical phenomenon-based cost functions, and an IMC-based feedback loop is implemented to gain robustness.

6. Simulation Results

In the development process of a controller, it is a critical stage to test it in a simulation environment. The structure can be validated, and there are broader possibilities to examine it with modified model and environmental parameters while all parameters are under control. Additionally, the simulation tests are much cheaper concerning time and money to be evaluated than the real-time measurements. In this section, the simulation results for comparing the proposed cost functions to the previous ones and the results of the measurements that are hard to be performed in real-time are presented.

The simulations were executed in a MATLAB and Simulink test environment called Vehicle Test Framework, developed by ThyssenKrupp. The framework consists of 12 degrees of freedom vehicle model with black box tire models developed by TNO automotive [35]. The simulator structure depicts the real-time environment structure: it consists of the localization block, emulation of the sensors with noise, actuators with modeled dynamics, and the vehicle model. The simulation has the same interface as the real-time system so that the same control algorithm can be run in both types of tests. The correspondence between the simulation and the real-time environment is verified by ThyssenKrupp. The parameters of the controller used in the simulation and in real-time can be seen in Table 2. The parameters of the tests were also identical in both measurements (maximal speed, size of the track, etc.) to have comparable results. These parameters were affected by the limitations of the available real-time test track.

6.1. Test Cases

There were three test scenarios defined based on the vehicle dynamics experiences of ThyssenKrupp and the literature to evaluate the robustness and perform the comparison of the cost functions:Low-mu lane change (referenced later as low-mu): the behavior of the controller under different friction coefficient conditions was tested in [36]. This test is based on the classical vehicle dynamics test: the lane change, but expanded with testing the resilience against friction coefficient changes. In this case, the classical lane change maneuver (the track is 5-meter wide and 28-meter long, composed of smooth clothoids) is performed under low-mu conditions with constant longitudinal speed .Double mass and inertia on lane change (referenced later as double): it is another test based on lane change, but it aims to examine the controller’s robustness concerning the internal parameter changes of the vehicle. Two simulation parameters of the 12DOF vehicle model were changed: , and the controller had to perform the maneuver, calculating with the original parameters, at a constant speed .Yaw rate step (referenced later as step): the robustness of the controller was tested with discontinuous reference in [36]. In this case, the most critical part, the yaw rate control properties of the controller, was tested by a special path: a straight line followed by an arc with a fixed radius. It means a step disturbance concerning the yaw rate reference and results nonminimum phase setting in the lateral error.

6.2. Examining the Performance

There were performance indicators implemented to have scalar values that can describe the behavior of the controller and can form the basis of comparisons. These indicators focus on the controlled values, the longitudinal speed , the lateral displacement from the path , and the control signals: and . The integral of the absolute error (IAE) is a common indicator measuring the difference between the reference signal and the actual one [17]. For the control signals, the most meaningful descriptor is the total energy used during the maneuvers. The proposed cost functions were also evaluated to see clearly its effect in the comparison. The indicators for comparing the cost functions are the following:The IAE of speed determines the reference tracking performance of the longitudinal control:The IAE of vehicle path determines the lateral path-following performance:where is the distance between the COG and the closest point of the path.The energy of steering is calculated from the change of the road-wheel angle :The energy in wheels is calculated from the requested breaking and driving torques:Integral of cost functions for the maneuver can base the comparison:The maximum value of the cost function during the maneuver emphasizes its effectiveness concerning safety:

The two min–max-based cost functions were compared to the corresponding quadratic-based ones by simulating the four test cases and evaluating the four indicator values. During the tests, all controller and simulation parameters were the same, except for the cost function. In the representation, the values of the evaluated indicators were normalized to the smaller value of the two indicator values of one test case.

Firstly, the proposed min–max-based cost function was compared to the previous sum of-squares-based, concerning the normalized force approach. Comparison of the two force-based cost functions performing the presented test cases can be seen in Table 3. In the low-mu case, the min–max-based cost function outperforms the summation-based, outstandingly in the integral value of the cost functions, ensuring safety for the maneuver. In some cases, the summation-based performs better executing the other two maneuvers. Still, this benefit is negligible concerning and , where the min–max-based is significantly better.

The difference concerning is significant in the step test as it can be seen in Figure 6. In this case, almost the same performance is provided by significantly lower torques and normalized forces.

The dissipation-based cost functions were also compared and evaluated by performing the three tests. The test results can be seen in Table 4. The reference tracking and control signal indicator values are better using the summation-based cost function in all cases. However, the min–max-based cost function performs even better in indicators and ; thus, it sacrifices a bit of performance to gain more safety.

7. Real-Time Tests

The real-time tests were performed at Tokol airport on an autonomous vehicle developed and supported by ThyssenKrupp. The Lotus Evora test vehicle can be seen in Figure 7. In this section, the structure of this vehicle is detailed, and after that, the results are presented and evaluated.

7.1. Real-Time Environment

The overall diagram of the real-time measurement setup can be seen in Figure 8. There are two independent electrical motors (denoted by ) connected to the rear wheels, each with 1400 Nm capacity. A TTC 200 electronic control unit drives the motors, and the actuator of the steering system is one of ThyssenKrupp’s control units. The four independent brakes (denoted by ) are by-wire solutions provided by Meccanica 42, overall with its driver system. The inner states are measured by inertial measurement unit (IMU) and differential global positioning system (DGPS) with dual antenna, providing orientation information.

The head of control in the vehicle is a real-time application running on MicroAutoBox II, developed in MATLAB and Simulink. This application is responsible for processing the measurement signals, calculating references with the localization algorithm, and handling actuators. Extended Kalman-filter-based state estimation is responsible for the vehicle state estimation. dSPACE Control Desk v6.4 provides the control interface of the real-time application. This software is responsible for the configuration of the vehicle and recording the measurement data. The real-time application is connected via a point-to-point UDP connection to an industrial PC that runs the optimization-based control algorithm under MATLAB r2020b.

There are prerecorded paths integrated into the real-time application that can be followed by the vehicle. Also, safety aspects are considered in the real-time environment. There should be a test driver sitting in the driver’s seat who can intervene in case of malfunction or forthcoming objects. The test driver can enable the autonomous mode of the vehicle by a remote controller.

7.2. Real-Time Results

In real-time, only the min–max-based cost functions were evaluated and compared to each other. The reference path for the tests was a closed-loop circle, ensuring the possibility of running multiple rounds, consisting of one broad turn, one sharper turn, lane change and double lane change maneuvers, and straight sections. In Figure 9, the performance of the proposed controller structure with the dissipation-based cost function can be seen in real-time measurement. The vehicle tracks the prerecorded closed-loop path and the longitudinal speed reference that changes in steps.

The inner loop was also tested, presenting yaw rate and longitudinal speed reference tracking to have a deeper insight into the performance of the controller. The comparison of the two cost functions for speed ramp and yaw rate step reference can be seen in Figure 10. It can be seen that when the step appears in the reference, the rear wheels are driven differentially by both cost functions. The force-based controller is more intensive in differential drive and less intensive in steering. Even if it consumes significantly more energy during its operation, this method can be preferred in some high dynamic cases when the steering is not fast enough.

In Figure 11, the comparison of the two cost functions is presented, running on the prerecorded track with constant speed, and the scalar descriptors were evaluated for the test. The results showed that there is no significant difference in the performance of longitudinal trajectory tracking and path following. It should be noted that the test circle does not approach close to the dynamical limitations of the vehicle, so the dissipation-based controller used differential driving only for a few moments.

The safety function of the real-time application can be applied as a disturbance generator during the controller tests. The test driver can override the steering value requested by the controller by forcing the steering to be turned. The robustness of the controller can be tested by performing the overriding test while the vehicle is at the straight section of the defined track. In Figures 12 and 13, the results of this test can be seen for the two cost functions. Both controllers can successfully eliminate the disturbance with the minimal number of steering movements, and an aperiodic setting eliminates the lateral error. The main difference is that the dissipation-based controller uses the differential driving only at the beginning when the yaw rate disturbance is high enough, and after that, during the “find back” section, only a small assist is given by the asymmetric rear wheels braking. Simultaneously, the force-based controller’s differential drive is active during the whole maneuver that can cause a high dissipation rate.

If the two methods are compared, it is clear that using the dissipation-based cost function leads to much smoother and more minor energy-consuming maneuvers than the force-based one. However, in some high dynamic cases, the force-based cost functions can have advantages in reference tracking. Therefore, the two different physical phenomena-based cost functions can lead us to understand the internal operation of varying driving styles and open the possibility of implementing those in autonomous robot vehicles.

8. Conclusion

In this paper, an optimization-based novel controller structure is presented. It is proven that the IMC-based controller structure provides robustness against parameter changes and external disturbances. The structure consists of two loops: the outer is a convex optimization-based reference generation for the lateral behavior of the vehicle. The inner loop is responsible for solving the control allocation problem for the underdetermined system considering physical limitations. The allocation problem can be solved using any second-order cone programming algorithm. Both optimizations use cost functions with physical meaning instead of heuristic multiobjective solutions, so no tuning weights are needed; intuitively tuned parameters are eliminated. The main focus of the method is minimizing the maximal values to be prepared for the worst cases. The proposed structure was tested in simulation, and the cost functions were compared and evaluated. Thanks to the problem formulation, the optimization tasks can be solved in real time, so test evaluations were performed on an autonomous test vehicle. The results support the efficiency of the proposed approach.

Data Availability

The data used to support the findings of this study are available from the corresponding author upon request.

Conflicts of Interest

The authors declare no conflicts of interest.

Acknowledgments

The authors would like to thank the support of the robot research group members at BME-AUT and the assistance of the members of the vehicle motion control at ThyssenKrupp. The research reported in this paper and carried out at the BME has been supported by the NRDI Fund based on the charter of bolster issued by the NRDI Office under the auspices of the Ministry for Innovation and Technology.