Next Article in Journal
Pointless Pose: Part Affinity Field-Based 3D Pose Estimation without Detecting Keypoints
Next Article in Special Issue
Dirt Loss Estimator for Photovoltaic Modules Using Model Predictive Control
Previous Article in Journal
Comparison of Different Design Alternatives for Hardware-in-the-Loop of Power Converters
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Fast Motion Model of Road Vehicles with Artificial Neural Networks

1
Department of Control for Transportation and Vehicle Systems, Budapest University of Technology and Economics, H-1111 Budapest, Hungary
2
Systems and Control Lab, Institute for Computer Science and Control, H-1111 Budapest, Hungary
*
Author to whom correspondence should be addressed.
Electronics 2021, 10(8), 928; https://doi.org/10.3390/electronics10080928
Submission received: 18 March 2021 / Revised: 5 April 2021 / Accepted: 7 April 2021 / Published: 13 April 2021
(This article belongs to the Collection Predictive and Learning Control in Engineering Applications)

Abstract

:
Nonlinear optimization-based motion planning algorithms have been successfully used for dynamically feasible trajectory planning of road vehicles. However, the main drawback of these methods is their significant computational effort and thus high runtime, which makes real-time application a complex problem. Addressing this field, this paper proposes an algorithm for fast simulation of road vehicle motion based on artificial neural networks that can be used in optimization-based trajectory planners. The neural networks are trained with supervised learning techniques to predict the future state of the vehicle based on its current state and driving inputs. Learning data is provided for a wide variety of randomly generated driving scenarios by simulation of a dynamic vehicle model. The realistic random driving maneuvers are created on the basis of piecewise linear travel velocity and road curvature profiles that are used for the planning of public roads. The trained neural networks are then used in a feedback loop with several variables being calculated by additional numerical integration to provide all the outputs of the original dynamic model. The presented model can be capable of short-term vehicle motion simulation with sufficient precision while having a considerably faster runtime than the original dynamic model.

1. Introduction

1.1. Literature Outlook

Automation of road transportation is expected to provide several benefits for society. Autonomous vehicles are expected to be more energy-efficient and environmentally friendly [1], while automated road traffic is predicted to improve average travel time significantly and traffic flow capacity [2], with the information provided by various sensors, communications and HD maps [3]. One of the most exciting research fields regarding autonomous driving is motion planning. Nonlinear optimization-based techniques have been used successfully to plan dynamically feasible trajectories for systems with nonholonomic dynamics. Optimization-based constrained trajectory generation algorithms are used for robot-assisted surgeries [4], machining equipment [5], and multi-purpose robots [6] as well as for road vehicles. One of the fundamental works on motion planning for wheeled vehicles is [7], where authors define an optimization framework suitable for driving a planetary robot on rough terrain. The winning team of the DARPA Urban Challenge at Carnegie Mellon University later used a similar nonlinear optimization-based trajectory planning and tracking algorithm [8]. In [9], the authors present a real-time fast and robust motion planning framework for urban conditions by combining a hybrid A*-based search with model predictive approaches to enable continuous re-planning based on current measurements. An optimization-based maneuver planning and tracking framework is proposed in [10] for low-speed and restricted-space environments using kinematic equations to describe the motion of cars, trucks, and semi-trailers. The authors of this paper propose a real-time trajectory planning algorithm in [11], where the dynamical feasibility of the motion is ensured by model-based simulation of the vehicle. The main difficulty in the case of all online optimization-based motion planning approaches is that the applied dynamical models have to be simulated numerous times as the cost and constraint functions need to be evaluated iteratively during the optimization loop. This means that considering an online optimization loop of approximately 100–200 ms, the available time for one vehicle simulation is in the range of 5 ms. Accordingly, there is an elementary need for fast and accurate short term vehicle simulation techniques in the field of optimal motion planning.
Numerous efficient simulation approaches have been developed for other time-critical applications such as computer graphics as well. In most cases, computer graphics functions require real-time performance for visualization, which means that the time available for the simulation of dynamic systems can often fall below even 1 ms. Position-Based Dynamics (PBD) directly computes the position-like dynamical quantities instead of time integration of equations of motions derived from Newton’s second law [12,13]. Subspace simulation methods are used to reduce the complexity of dynamic models by projecting the equations of motion into a reduced subspace with the help of, e.g., Principal Component Analysis (PCA) for a more efficient solution [14,15]. Data-driven physical simulations use data precomputed offline by accurate dynamic simulation techniques to approximate and/or accelerate online simulations. Artificial neural network-based data-driven models are an attractive opportunity for time-critical simulations because they enable faster run-times at the price of offline pre-calculations and higher memory usage [16,17]. Researchers at Ubisoft and McGill University are combining subspace simulation techniques with supervised learning in a computer graphics application where the computation time available for one object is in the range of 10–100 microseconds to simulate deformation effects, collisions of objects, and external forces [18].
Artificial neural networks are already used in vehicle simulation and control applications as well. In [19], authors are using artificial neural networks for modeling the main combustion metrics of diesel engines as an alternative for parameter tuning of dynamical models. Authors in [20] are simulating vertical tire and suspension dynamics while traversing road irregularities with recurrent neural networks. Another worthy example is [21], where deep feedforward networks are used to model and simulate a hovercraft. A robust neural network-based lateral control method is proposed in [22], which aims to resolve high-frequency oscillation issues of classical Sliding Mode Control (SMC) with the application of Radial Basis Function Neural Networks (RBFNN). Similarly, authors of [23] combine Model Predictive Control (MPC) with RBFNN to robustly handle the nonlinear characteristics of the steering system. A reinforcement-learning-based integrated planning and control method is proposed for automated parking applications in [24], which can simultaneously coordinate the longitudinal and lateral motions to park in a smaller parking space in one maneuver. Reinforcement learning is also used for high velocity lane change maneuvering in [25], where a Deep Deterministic Policy Gradient (DDPG) agent is utilized in an end-to-end method using lidar data. The authors of this paper are also actively researching this field. In [26], a hybrid motion planning approach is presented that unites classical optimization with neural networks for the more efficient solution of the planning problem. A reinforcement-learning-based lane keeping planning algorithm is developed in [27], where the machine learning agents are applied to support the Monte Carlo Tree Search (MCTS)-based planning in order to provide real-time performance.
As shown, artificial neural networks have been successfully utilized for physical simulations in numerous different research fields to enhance simulation speeds or replace physical models with many parameters.

1.2. Motivation

The motivations to create a neural network based vehicle model are twofold. Firstly, one can train the neural network based on real vehicle measurement data. This would enable us to perform simulations that are completely tailored to the vehicle in question, without having to worry about the correct parametrization of a dynamic model with a high degree of freedom. Secondly, the neural network can also be trained based on simulated vehicle motion data using a dynamic model of arbitrary complexity. The goal and expected benefit here is to decrease computational effort and thus runtime of the simulations using the neural-network-based model. Fast vehicle motion simulations of several (≤10) s are extremely useful for the application in online optimization-based motion planner algorithms as the evaluation of cost and constraint functions inside the optimization loop requires predicting the vehicle’s motion in case of numerous different values of the optimized variable [28]. This often means several hundreds of simulations that can be done faster with the neural-network-based model. The plausibility of the optimization results obtained this way can subsequently be supervised with a simulation of the original dynamic model. A single simulation does not cause runtime issues, even with a fairly complex vehicle model.
The contribution of this paper is accordingly a neural-network-based road vehicle model that is able to substitute a classic nonlinear single-track dynamical model in short-term simulations, while being faster as well. The paper is organized as follows. First, Section 2 describes the original dynamic model of the vehicle. In Section 3, a random trajectory planning algorithm is shown that is used to generate learning data for the neural-network-based approach. Then, in Section 4, the neural-network-based vehicle model is presented in details. Simulation results and performance evaluation of the proposed algorithm are described in Section 5. The limitation and potential issues of this study are later discussed in Section 6. Finally, Section 7 contains concluding remarks and proposals for future research directions.
Figure 1 shows the progress of the presented research from our motivation to create a neural-network-based vehicle model to the proof of concept of the developed method.

2. Nonlinear Single Track Vehicle Model

In this section, the applied planar nonlinear single-track vehicle model will be presented in detail. Planar single-track models are widely used for vehicle simulations and model-based calculations because they can offer sufficient precision in most driving scenarios on public roads while having a moderate complexity. Authors use the presented model in optimization-based motion planning algorithms as well, which makes it a good candidate for the proof of concept of the proposed neural-network-based model. The presented model combines literature sources, focusing on either chassis or wheel dynamics by using a sophisticated dynamic wheel slip model to increase the precision of simulations and also extends them with practical considerations that enable a stable and efficient numerical solution. Standard notations used for the equations of the vehicle model are the following. Superscripts differentiate between the same quantities in different coordinate systems. Specifically, superscript G stands for global inertial coordinate system NWU (North West Up), superscript V denotes the rotating vehicle-fixed coordinate system, and superscript W is applied for quantities in wheel-fixed coordinate systems. As numerous equations have to be calculated both for front and rear wheels the same way, subscript [ f / r ] is used many times to indicate that by selecting subscript f or r for the whole equation, respectively, the equations are shown for both wheels. Similarly, subscript [ x / y ] is used when the calculations for longitudinal and lateral directions are equivalent.

2.1. Model Components

The presented nonlinear single-track vehicle model shown in Figure 2 is a planar rigid multi-body model. The term single-track means that the wheels at the front and rear axles are substituted by one wheel per axle. Single-track models are widely used for vehicle simulations and model-based calculations because they can offer sufficient precision in most driving scenarios while having a moderate complexity [29]. The multi-body model consists of 3 bodies; the vehicle chassis and the two wheels, which are connected rigidly. Our model is planar, which means that vertical translation and roll and pitch movements are completely neglected. The vehicle is subject to Earth’s gravitational acceleration g. The center of gravity location of the vehicle is considered to be constant.
Wheel slips are modeled dynamically with respect to the elasticity of the tires. The longitudinal and lateral tire forces are nonlinear functions of corresponding wheel slips with respect to their simultaneous presence (superposition of forces is considered). Aligning torques on the wheels due to lateral slip is neglected. The vehicle has front-wheel steering, and the dynamics of steering actuation are considered. Driving inputs consist of total driving and braking torques as well as the steering wheel angle.
The presented model can precisely simulate driving scenarios even with high accelerations at the limit of adhesion and stability while having a moderate computational effort compared to full four-wheel 3D models. However, it cannot consider vertical dynamic effects such as road unevenness or load transitions due to road slope. Furthermore, scenarios where all four wheels’ friction conditions play an important role, such as μ -split cases—where the left and right side of the vehicle meets with different road surface—cannot be simulated.

2.2. Dynamics of the Chassis

The vehicle chassis is a rigid planar body with three degrees of freedom: longitudinal and lateral positions x v G and y v G and yaw angle ψ v in the global inertial coordinate system. The chassis’ equations of motion represent the principles of conservation of linear and angular momentum (Newton’s second law) and are expressed in the inertial global coordinate system as follows:
x ¨ v G = 1 m v ( F f a , x G + F r a , x G + F d , x G ) ,
y ¨ v G = 1 m v ( F f a , y G + F r a , y G + F d , y G ) ,
ψ ¨ v = 1 θ v , z ( l v , f F f a , y V l v , r F r a , y V ) ,
where m v is the total mass of the vehicle, θ v , z is its the moment of inertia about the vertical axis, and horizontal distances of vehicle center of gravity to front and rear axles are noted by l v , [ f / r ] . Aerodynamic drag forces are first calculated in the vehicle-fixed coordinate system as
F d , x V = 1 2 c v , d A v , f ρ A x ˙ v V ( x ˙ v V ) 2 + ( y ˙ v V ) 2 ,
F d , y V = 1 2 c v , d A v , f ρ A y ˙ v V ( x ˙ v V ) 2 + ( y ˙ v V ) 2 ,
where A v , f is the frontal area and c v , d is the aerodynamic drag coefficient of the vehicle, while ρ A is the density of air [29]. The conversion of arbitrary dynamic quantity γ [ x / y ] in the rotating vehicle-fixed coordinate system to the global inertial one is done by
γ x G = + cos ( ψ v ) γ x V sin ( ψ v ) γ y V ,
γ y G = + sin ( ψ v ) γ x V + cos ( ψ v ) γ y V .
Similarly, the conversion from the global inertial coordinate system to the vehicle-fixed is
γ x V = + cos ( ψ v ) γ x G + sin ( ψ v ) γ y G ,
γ y V = sin ( ψ v ) γ x G + cos ( ψ v ) γ y G .
Accordingly, the aerodynamic drag forces calculated in Equations (4) and (5) are transformed to the inertial global coordinate system by Equations (6) and (7). As the model is planar (vertical movements are neglected), one can calculate the tire loads based on equilibrium of forces and moments in the vertical plane as
F f , z V = m v g l v , r h v ( F f a , x V + F r a , x V ) l v , f + l v , r ,
F r , z V = m v g l v , f + h v ( F f a , x V + F r a , x V ) l v , f + l v , r ,
where h v is the center of gravity height of the vehicle. Driving and braking torques are distributed ideally according to the load transfer above, which means the resulting longitudinal slips shall be equalized by torques calculated as
M [ f / r ] , d = c [ f / r ] , M c f , M + c r , M M d ,
M [ f / r ] , b = c [ f / r ] , M c f , M + c r , M M b ,
with c [ f / r ] , M = r [ f / r ] F [ f / r ] , z V where M d and M b are the non-negative driving and braking torque inputsb [30]. Calculation of the applied longitudinal and lateral tire forces F [ f / r ] a , [ x / y ] ( · ) is detailed in Section 2.3.
We are often interested in the inertial accelerations not only in the global coordinate system, but in the vehicle-fixed one as well. To calculate their values x ¨ v , I V , y ¨ v , I V , from global accelerations x ¨ v G , y ¨ v G we can use Equations (8) and (9). Please note that these accelerations are not equal to the translational accelerations in the vehicle-fixed system, because the vehicle is rotating.

2.3. Dynamics of the Wheels

The front and rear virtual wheels have a single degree of freedom: rotation about their own axes ρ [ f / r ] . Longitudinal and lateral wheel slips s [ f / r ] , [ x / y ] are calculated according to a dynamic model considering elasticity of the tires. The dynamic equations of the wheels are as follows:
ρ ¨ [ f / r ] = 1 θ [ f / r ] M [ f / r ] , d r [ f / r ] F [ f / r ] a , x W M [ f / r ] , b a M [ f / r ] , r r a ,
s ˙ [ f / r ] , x = 1 l [ f / r ] a , x v [ f / r ] , r x ˙ [ f / r ] W | x ˙ [ f / r ] W | s [ f / r ] , x ,
s ˙ [ f / r ] , y = 1 l [ f / r ] a , y y ˙ [ f / r ] W | x ˙ [ f / r ] W | s [ f / r ] , y ,
where r [ f / r ] are the radii and θ [ f / r ] are the moments of inertia of the wheels. The rolling velocities of the wheels are calculated as
v [ f / r ] , r = r [ f / r ] ρ ˙ [ f / r ] .
The braking torque shall only be applied to the wheels if they are moving, calculated as
M [ f / r ] , b a = sign ( v [ f / r ] , r ) M [ f / r ] , b , if v [ f / r ] , r > v b a sign ( v [ f / r ] , r ) M [ f / r ] , b 1 2 1 cos π | v [ f / r ] , r | v b a , if v [ f / r ] , r v b a
where v b a = v b a , 0 + k v b a | M [ f / r ] , b | is the rolling velocity at which braking torque damping should disappear. With this approach, the value of applied braking torque is gradually built down as the wheel stops, so that it can reach an oscillation-free standstill state. Rolling resistance torques are first calculated as
M [ f / r ] , r r = sign ( v [ f / r ] , r ) F [ f / r ] , z W r f [ A r r + B r r | v [ f / r ] , r | + C r r ( v [ f / r ] , r ) 2 ] ,
where A r r , B r r , and C r r are parameters [31]. Tire loads are the same in the vehicle-fixed and in the wheel-fixed coordinate systems F [ f / r ] , z W = F [ f / r ] , z V due to the common vertical axis. Then, a damping technique similar to one applied to the acting braking torque is used to eliminate discontinuity at point v [ f / r ] , r = 0, so that the acting rolling resistance torques are built up gradually while the wheels are starting to move as follows:
M [ f / r ] , r r a = M [ f / r ] , r r , if v [ f / r ] , r > v r r a M [ f / r ] , r r 1 2 1 cos π | v [ f / r ] , r | v r r a , if v [ f / r ] , r v r r a
where v r r a is the rolling velocity at which rolling resistance torque should be fully applied.
Tire forces are generally calculated as a function of slip according to the Magic Formula in the coordinate systems of corresponding wheels as
F [ f / r ] , [ x , y ] W ( s ) = μ [ f / r ] F [ f / r ] , z W D [ f / r ] , [ x , y ] sin { C [ f / r ] , [ x , y ] arctan ( B [ f / r ] , [ x , y ] s E [ B [ f / r ] , [ x , y ] s arctan ( B [ f / r ] , [ x , y ] s ) ] ) } ,
where μ [ f / r ] is the static coefficient of friction and D [ f / r ] , [ x , y ] are the maximum factors, C [ f / r ] , [ x , y ] are the shape factors, B [ f / r ] , [ x , y ] are the stiffness factors, and E [ f / r ] , [ x , y ] are the curvature factors of the tire model [32]. To improve the low-speed behavior of the model especially when starting from or braking until standstill, the tire forces are calculated based on damped slip values [32], which are evaluated as
s [ f / r ] d , x = s [ f / r ] , x + k [ f / r ] d , x K [ f / r ] , x v [ f / r ] , r x ˙ [ f / r ] W ,
s [ f / r ] d , y = s [ f / r ] , y ,
with slip stiffness being
K [ f / r ] , [ x , y ] = μ [ f / r ] F [ f / r ] , z W D [ f / r ] , [ x , y ] C [ f / r ] , [ x , y ] B [ f / r ] , [ x , y ] .
The factor of slip damping is calculated with the usual cosine transition as
k [ f / r ] d , x = 0 , if x ˙ f W > v s d k [ f / r ] , x 1 2 1 + cos π | x ˙ f W | v s d , if x ˙ f W v s d ,
where v s d is the rolling velocity at which slip damping should switch off and k [ f / r ] , x is the initial maximal factor of damping [32]. In case of pure longitudinal or lateral slip conditions, the tire forces are calculated simply by
F [ f / r ] n , [ x , y ] W = F [ f / r ] , [ x , y ] W ( s [ f / r ] d , [ x / y ] ) .
In case of the mutual presence of longitudinal and lateral wheel slips tire forces are calculated with respect to their superposition by the friction ellipse method, given as
F [ f / r ] c , x W = sign ( s [ f / r ] d , x ) F [ f / r ] , x W s [ f / r ] d , c F [ f / r ] , y W s [ f / r ] d , c 2 F [ f / r ] , y W s [ f / r ] d , c 2 + s [ f / r ] d , y s [ f / r ] d , x F [ f / r ] , x W s [ f / r ] d , c 2 ,
F [ f / r ] c , y W = sign ( s [ f / r ] d , y ) F [ f / r ] , x W s [ f / r ] d , c F [ f / r ] , y W s [ f / r ] d , c 2 F [ f / r ] , x W s [ f / r ] d , c 2 + s [ f / r ] d , x s [ f / r ] d , y F [ f / r ] , y W s [ f / r ] d , c 2 .
with s [ f / r ] d , c = ( s [ f / r ] d , x ) 2 + ( s [ f / r ] d , x ) 2 being the combined slip value. Finally, the acting tire forces are given by
F [ f / r ] a , [ x / y ] W = F [ f / r ] c , [ x / y ] W if s [ f / r ] d , [ x , y ] > s d a , F [ f / r ] n , [ x / y ] W if s [ f / r ] d , [ x , y ] s d a ,
where s d a is the minimal value of wheel slips where superposition of forces shall be considered. This limit is important for the numerical calculations, as Equations (27) and (28) are singular at zero slip values. The acting tire forces of the front wheel given in its own coordinate system F f a , [ x / y ] W can be transformed to the values in the vehicle-fixed frame F f a , [ x / y ] V by substituting the yaw angle ψ v with steering angle δ f in Equations (6) and (7). Since the vehicle has front wheel steering only, conversion for the rear wheels is not necessary as F f a , [ x / y ] V = F f a , [ x / y ] W . Further conversions from forces in the vehicle-fixed coordinate system F [ f / r ] a , [ x / y ] V to the ones in the global inertial coordinate system F [ f / r ] a , [ x / y ] G can be performed directly according to Equations (6) and (7).
To be able to evaluate the dynamic equations of the wheel, slip-dependent acting relaxation lengths of tires have to be calculated as
l [ f / r ] a , [ x / y ] = m a x l [ f / r ] , [ x / y ] 1 K [ f / r ] , [ x , y ] 3 D [ f / r ] , [ x , y ] | s [ f / r ] , [ x , y ] | , l [ f / r ] m , [ x / y ] ,
where l [ f / r ] , [ x / y ] and l [ f / r ] m , [ x / y ] are the relaxation lengths at standstill and at wheel spin or lock, respectively [32]. Furthermore, the velocities of wheel center points are needed in wheel-fixed coordinate systems. To obtain these, the velocities of the vehicle center of gravity in the global inertial coordinate system x ˙ v G y ˙ v G are first converted to the vehicle-fixed coordinate system x ˙ v V x ˙ v V with Equations (8) and (9). Then, wheel center point velocities are calculated as
x ˙ [ f / r ] V = x ˙ v V ,
          y ˙ f V = y ˙ v V + l v , f ψ ˙ v ,
          y ˙ r V = y ˙ v V l v , r ψ ˙ v .
The wheel center point velocities finally have to be transformed to wheel-fixed coordinate systems. For the rear wheel, no real transformation is necessary as x ˙ r W = x ˙ r V and y ˙ r W = y ˙ r V . As the front wheel is steered, Equations (8) and (9) can be used with the substitution of yaw angle ψ v with steering angle δ f to get the values x ˙ f W and y ˙ f W .

2.4. Steering Actuation

The vehicle model uses a simple first-order transfer function to consider the steering actuator. The steering dynamics are given by
δ ˙ f = k s T s δ s w 1 T s δ ,
where δ s w is the steering wheel angle input, k s is the steering ratio, and T s is the settling time of the steering mechanism. The trajectory tracking behavior of the vehicle is much more realistic, even with this very simple actuation model, than with the direct application of steering angles calculated by the tracking controllers.

2.5. Closed Loop Control

In order to follow a selected reference trajectory, we need tracking controllers to drive the presented vehicle model with control inputs—driving and braking torques and steering wheel angle. Longitudinal speed tracking control is performed by a state feedback LQR (Linear Quadratic Regulator) controller according to
M d b = K v 1 x ˙ v V K v 2 z v
where K v 1 and K v 2 are gain values and z v is the integral of velocity tracking error. The longitudinal controller computes a signed torque value which is then transformed to the non-negative driving inputs as
M d = max ( M d b , 0 ) ,
M b = | min ( M d b , 0 ) . |
Path tracking is realized by a Stanley controller. This is a nonlinear feedback control that ensures asymptotic tracking of the reference path. According to the control law, the wheel level steering angle of the front axle is calculated as
δ f = e ψ + arctan ( K s t e l a t x ˙ v V ) ,
where e ψ is the yaw angle offset between the path and the vehicle, e l a t is the lateral distance of the front axle center-point from the path, and K s t is a tunable gain parameter [33]. The reference point for tracking error calculation is the closest point of the path curve to the center of the front axle.

2.6. Simulation of Model

The motion of the presented dynamic nonlinear single-track vehicle model must be calculated numerically by an Ordinary Differential Equation (ODE) solver with an appropriate time resolution. As a solver, we recommend second (Heun) or fourth-order (RK4) explicit Rungke–Kutta methods as they provide stable and fast computations. For reproducibility and convenient manageability of simulation output, a fixed step-size is used. Due to the wheels’ relatively fast and complex dynamics (especially in drive-off or brake-still scenarios), a relatively small step size Δ t v around 1 ms is required.

3. Random Trajectory Planning

Overall, the presented vehicle dynamics model has 15 states and five inputs, which have to be provided to the state equation to calculate state derivatives. With this number of variables, training sample generation by parameter sweeping is impossible. Considering only ten values for each input, the number of samples would reach 1.024 × 1013, which is very difficult to handle. Instead of the parameter sweeping, learning data are generated based on simulated scenarios. When defining the driving maneuvers, our goal is to create a wide variety of dynamic situations. Regarding longitudinal dynamics, sections with intensive acceleration and braking and smaller variations around a constant traveling velocity are necessary. Considering lateral dynamics, mild curves, as well as sharp turns, are essential to reach an extensive range of lateral acceleration. Combinations of curves with acceleration and braking are also desirable. Definition of these simulation maneuvers manually would be, on the one hand, a massive effort. On the other hand, it would probably also not provide the required diversity. Thus, a randomized motion planning approach is applied to generate the reference data for vehicle dynamics simulations.

3.1. Motion Planning Based on Piecewise Linear Curvature and Travel Velocity Functions

The idea of path planning based on a piecewise linear curvature function comes from the real world, as horizontal geometry (alignment) of public roads in most cases consists of straight segments and circular arcs, connected by clothoid curves for a smooth transition [34]. While straight segments have zero curvature, and circular arcs have a constant curvature, the clothoid’s curvature is changing linearly with the arc length. Thus, road geometries in question can be defined by assigning a piecewise linear curvature profile as a function of the arc length along the path. Naturally, continuous derivative profiles could also be used, but their implementation would increase the complexity of the algorithm without giving a real benefit for the current application [35]. To get a driving trajectory, we also have to specify the traveling speed of the vehicle. This can be done simply and sufficiently by defining a piecewise linear speed profile as a function of time. Naturally, the curvature and speed profiles must be connected to provide a feasible trajectory—e.g., we have to slow down before high-curvature (low radius) sections.
Accordingly, the input of the trajectory planner is
X p = σ p i κ p i x ˙ p i T , i = 1 N p i ,
where σ p i are the arc length, κ p i are the curvature, and x ˙ p i are the traveling velocity knot points of the curvature and velocity profiles. The meaning of the input parametrization is that at arc length σ p i , the curvature of the path shall be κ p i and the travel velocity shall be x ˙ p i . Figure 3a (in blue) shows the input of the planning.
The time needed to travel along each path section can be calculated by
Δ t p i = Δ σ p i x ˙ p i ,
where Δ σ p i = σ p i + 1 σ p i and x ˙ ˜ p i = x ˙ p i + x ˙ p i + 1 2 for i = 1 N p i 1 . The travel time at each knot point is then
t p i + 1 = 1 i Δ t p i ,
for i = 1 N p i 1 with t 1 = 0 . The constant longitudinal acceleration along each path section is given by
x ¨ p i = Δ x ˙ p i Δ t p i ,
where Δ x ˙ p i = x ˙ p i + 1 x ˙ p i for i = 1 N p i 1 . For any arc length such that σ p [ σ p i , σ p i + 1 ] the travel time can be expressed as
t p = σ σ p i x ˙ p i + t p i if x ¨ p i = 0 , x ˙ p i + ( x ˙ p i ) 2 + 2 x ¨ p i ( σ σ p i ) x ¨ p i + t p i if x ¨ p i 0 ,
Based on the time information, travel velocity is calculated as
x ˙ p = x ˙ p i + x ¨ p i ( t p t p i ) .
By obtaining curvature with a simple interpolation
κ p = κ p i + κ p i + 1 κ p i σ p i + 1 σ p i σ p ,
yaw rate and centripetal acceleration are
ψ ˙ p = x ˙ p κ p ,
y ¨ p = x ˙ p ψ ˙ p .
To be able to evaluate path coordinates, yaw (heading) angle is first calculated as
ψ p = ψ p , 0 + 0 σ p ψ ˙ p ,
where ψ p , 0 initial yaw angle is assumed for every trajectory. Then, longitudinal path coordinates can be calculated as
x p = x p , 0 + 0 σ p cos ( ψ p ) d s ,
and lateral path coordinates are evaluated as
y p = y p , 0 + 0 σ p sin ( ψ p ) d s ,
with the assumptions of x p , 0 = 0 and y p , 0 = 0 . In practice Equations (40)–(42) are first calculated for each input knot points. Then, the total arc length domain is split with equidistant steps as
σ p j = j σ p , s , j = 0 N p j
where σ p , s (0.1 m) is a suitable step size and N p j = σ p N p i σ p , s . Equations (43)–(50) are then numerically calculated for the resulting arc length series. The output of the planner accordingly is
Y p = x p j y p j ψ p j ψ ˙ p j , T , j = 0 N p j ,
and contains a series of path coordinates as well as yaw angle and yaw rate values along the trajectory that can be used as reference for vehicle dynamics control. The outputs of the trajectory planner can be seen on Figure 3b.

3.2. Random Planning

It is evident that we cannot just specify any input to the trajectory planner described in Section 3.1 to get a feasible trajectory. The calculations in the planner are solely geometric and are assuming that the traveling object is precisely following the given path and velocity. This means that the random trajectory planning must be constrained to provide a feasible reference to the vehicle simulation. The number of road sections N r (500) is chosen in advance (this means that number of profile knot points N p i will be 501). The planning is carried out as follows.
  •  The knot points x ˙ p i of the traveling velocity profile are chosen randomly between allowed lower x ˙ p , m i n (10 m/s) and upper x ˙ p , m a x (30 m/s) limits.
  •  Minimal allowed radii are calculated for each section based on maximal allowed lateral acceleration y ¨ p , m a x (5 m/s2).
    r p , m i n i = ( x ˙ p i ) 2 y ¨ p , m a x
  •  Radii r p i of each section are chosen randomly in such a way that the values are between r p , m i n i and m r m i n r p , m i n i . The factor m r m i n (10) is a planning parameter.
  •  Lengths Δ σ p i of each section are chosen randomly in such a way that the values are between p c m i n 2 π r p i and p c m a x 2 π r p i . The factors p c m i n (0.1) and p c m a x (0.2) are planning parameters.
  •  Curvature values κ p i = 1 r p i are calculated, and half of them are inverted to provide left and right turns with equal probability.
  •  A p s (0.35) proportion of the curvature values κ p i is nulled out to provide straight segments in a way that neighboring straight segments are not allowed.
  •  Transitions are calculated between each of the previous sections in such way that the proportion of their lengths to the segments lengths p t (0.4) is given.
  •  Arc length knot points σ p i are calculated by a cumulative sum of segment lengths Δ σ p i .
  •  The curvature and travel velocity profile calculated in 1–8 is then provided to the planner described in Section 3.1 to get the random reference trajectory.
Example trajectories designed with the algorithm detailed in this section are shown in Figure 4.

4. Neural Network Based Vehicle Model

In this section, the developed neural-network-based vehicle model will be presented in detail. Our main goal with the presented algorithm is to provide quick neural-network-based vehicle simulations of maximally about 10 s, which can be obtained faster than the original dynamic model’s solution to use them in the online optimization loop of motion planner algorithms. First, the input–output structure, as well as the method of learning sample generation, is explained. Then, the architecture of used neural networks as well as the training process is shown. Last, the algorithm for vehicle motion simulation based on the trained neural networks is presented. For the modeling and training of artificial neural networks, we use the Python programming language and its packages tensorflow, keras and scikit-learn. The training is performed on a desktop computer with an Intel® Core™ i5-7600 CPU, 32 GB of RAM, 500 GB of NVME SSD storage, and an NVIDIA® GeForce GTX 1050 Ti GPU.

4.1. Input–Output Concept

The first important aspect of artificial-neural-network-based vehicle modeling is the input–output structure of the model. On the one hand, the artificial neural network could be used to estimate the equations of motion of the vehicle Equations (1)–(3), (14)–(16). With this approach, the output of the neural network consists of the same translational and angular accelerations that the original dynamic equations provide and thus must still be integrated the same way with an ODE solver and 1ms time step. As explored in earlier stages of the research, this approach has two significant disadvantages. As described in Section 1.2, the main goal of the neural-network-based model would be to decrease run-time of motion predictions. Firstly, the computation time of recalling the neural network should be less than the computation time of the original state equation, which strongly restricts the number of neurons usable in the network. Secondly, the estimation errors of the neural network are amplified by the ODE solver, causing the solution to diverge quickly. Due to the mentioned drawbacks, this approach is not presented in the paper.
On the other hand, direct estimation of the solution of the equations of motion of the vehicle is also possible. The aim here is to predict the vehicle’s state at time t + Δ t n v based on its state and input at time t, namely, to provide the solution of the ODEs for a time span of multiple 1 ms steps. Four different input–output variants were examined for this concept in the research, which are noted with V0, V1, V2, and V3, respectively. The input vector of the neural network consists of the inputs and a subset of state variables of the dynamic model at a given time t and is represented as
X n v V 0 , V 1 ( t ) = M d b ( t ) δ s w ( t ) x ˙ v V ( t ) y ˙ v V ( t ) ψ ˙ v ( t ) ρ ˙ f ( t ) s f , x ( t ) s f , y ( t ) ρ ˙ r ( t ) s r , x ( t ) s r , y ( t ) δ f ( t ) , X n v V 2 , V 3 ( t ) = M d b ( t ) δ s w ( t ) ψ v ( t ) x ˙ v V ( t ) y ˙ v V ( t ) ψ ˙ v ( t ) ρ ˙ f ( t ) s f , x ( t ) s f , y ( t ) ρ ˙ r ( t ) s r , x ( t ) s r , y ( t ) δ f ( t ) .
The only difference in the input vectors of different variants is that yaw angle ψ v ( t ) is additionally provided for the V2–3 networks. The output vector of the neural network consists of the changes of a subset of vehicle state variables as time reaches t + Δ t n v , calculated as
Δ ξ ( t ) = ξ ( t + Δ t n v ) ξ ( t )
for a general state variable ξ , and is represented as
Y n v V 0 ( t ) = Δ x ˙ v V ( t ) Δ y ˙ v V ( t ) Δ ψ ˙ v ( t ) Δ ρ ˙ f ( t ) Δ s f , x ( t ) Δ s f , y ( t ) Δ ρ ˙ r ( t ) Δ s r , x ( t ) Δ s r , y ( t ) Δ δ f ( t ) , Y n v V 1 . V 2 ( t ) = Δ ψ v ( t ) Δ x ˙ v V ( t ) Δ y ˙ v V ( t ) Δ ψ ˙ v ( t ) Δ ρ ˙ f ( t ) Δ s f , x ( t ) Δ s f , y ( t ) Δ ρ ˙ r ( t ) Δ s r , x ( t ) Δ s r , y ( t ) Δ δ f ( t ) , Y n v V 3 ( t ) = Δ x v G ( t ) Δ y v G ( t ) Δ ψ v ( t ) Δ x ˙ v V ( t ) Δ y ˙ v V ( t ) Δ ψ ˙ v ( t ) Δ ρ ˙ f ( t ) Δ s f , x ( t ) Δ s f , y ( t ) Δ ρ ˙ r ( t ) Δ s r , x ( t ) Δ s r , y ( t ) Δ δ f ( t ) .
The difference in the output vectors of different variants is that networks V1–3 directly estimate the heading angle difference Δ ψ v , and network V4 directly estimatwa the changes in position Δ x v G and Δ y v G as well.

4.2. Learning Sample Generation

As the first step of the learning sample generation, random reference trajectories are generated by the motion planner described in Section 3. For current work, an equivalent amount of 10 h (∼680 km) driving was generated for training and another 4 h (∼270 km) for testing purposes, which means a 70–30% train-test split, approximately. Then, vehicle simulation was performed with the model described in Section 2 with a sample time of Δ t v = 1 ms. In order to provide the same amount of left and right turns to the learning process, data augmentation was used by mirroring (inverting the lateral motion components of) the simulated trajectories. Accordingly, an equivalent of 28 h of driving data were generated in total.
For the next step, the prediction time Δ t n v of the neural-network-based model has to be decided. On the one hand, the bigger this value is, the faster the motion prediction with the network will be. On the other hand, as the model is intended to be used in a motion planner algorithm, a certain resolution is necessary for reliable collision avoidance calculations. From the feasible set of prediction time values of 5, 10, 20, and 50 ms, Δ t n v = 10 ms was chosen as it provides a sufficient trade-off between run-time and resolution. The complete matrices of training input and output samples are then
I n v t r = X n v ( 0 ) X n v ( Δ t v ) X n v ( 2 Δ t v ) X n v ( ( N v t r 1 ) Δ t v Δ t n v ) T ,
O n v t r = Y n v ( 0 ) Y n v ( Δ t v ) Y n v ( 2 Δ t v ) Y n v ( ( N v t r 1 ) Δ t v Δ t n v ) T ,
where N v t r is the total number of training vehicle simulation samples. Testing input I n v t t and output O n v t t samples are generated in the same way from the corresponding vehicle simulation samples. Maximum absolute values are calculated for each input and output variables separately for scaling as
c X n v = max t X n v ( t ) ,
c Y n v = max t Y n v ( t ) ,
commonly for training and testing samples. Both the input and output samples are then scaled in each variable (along each column) with these scales so that they only contain values in range of [−1, 1]. From the 28 h of driving data, approximately 70 million training samples as well as 28 million test samples were generated.
Since vehicle simulations are written in C++ for better performance and data preparation is mainly done in MATLAB, learning data must be written into files to be able to use them in Python for the training. Due to a large number of learning data (more than 16 GB), samples do not all fit into computer memory at once. For efficiency, learning input and output matrices I n v t r and I n v t t as well as O n v t r and O n v t t are written into multiple binary files in a column major order with one binary buffer containing 1024 batches of 8196 samples. The scaling vectors c X n v and c Y n v are also written to column major binary files for uniform data handling. Training metadata (number of inputs, outputs, samples, batch size, buffer size, variable names) are written to a JSON (JavaScript Object Notation) file for convenience.
To efficiently provide the learning data from the binary buffers, an own generator algorithm is necessary, which reads in the files only once per training epoch in a subsequent order. To achieve this, shuffling of learning data must be switched off in kerasModel.fit method so that the training algorithm asks for the samples in increasing order. By knowing the number of samples per binary file from the metadata, it is easy to decide if a new file must be loaded. The generator algorithm also takes care of the shuffling of samples per buffer file by creating random indices for samples.

4.3. Neural Network Architecture

The estimation of vehicle simulation output is a regression task. For this, fully connected feed-forward deep neural networks are used with three or four intermediate layers and 256 neurons in total. Trying networks with a total neuron count of 96, 128, and 384 shows that with fewer neurons, the fitting results are much worse, and with more neurons, the slight improvement in performance is not worth the increased computational effort. For each I/O variant V1–4, four different networks are trained with layouts shown in Table 1.
As an activation function, ReLU (Rectified Linear Unit) is applied for each layer except for the output layer using linear activation. Experimenting with other activation functions such as sigmoid, hyperbolic tangent, or SELU (Scaled Exponential Linear Unit) shows worse performance without exception.

4.4. Training Process

To compute the loss during the training, a custom weighted mean squared error function is used as
L n v = 1 n Y n v i = 1 n Y n v w L n v i ( Y n n i Y ^ n n i ) 2 ,
where n Y n v is the number of elements of the output vector, w L n v i are custom weighting factors for each output variable, and prediction of neural network is denoted with Y ^ n n . The rationale behind using this weighted loss instead of the standard mean squared error loss is that the precision of velocity and position predictions is more important than, for instance, the slip variables.
The Adam optimizer waschosen, which is a stochastic gradient descent method that is based on adaptive estimation of first-order and second-order moments. Adam optimizer is generally recommended as “computationally efficient, has little memory requirement, invariant to diagonal rescaling of gradients, and is well suited for problems that are large in terms of data/parameters” [36]. Learning rate multipliers 0.1, 0.3, 0.5, and 1 are applied to the default value of learning rate 0.001 to search for optimal training results.
Learning progress of the neural networks reaching the smallest final loss is shown in Figure 5. On the left side, the best results are shown for each topology in Table 1. On the right side, the results for the best network overall are shown. The number of training epochs is chosen as 100 for a balance between training time and performance. Batch size is selected for 8196 samples. The training time of a network with a single set of parameters is approximately 1 h due to the learning samples not fitting into memory at once. With the selected number of training epochs, no overfitting is visible. An increased number of 140 training epochs shows no real performance improvement.

4.5. Motion Prediction in Feedback Loop

As explained in Section 4.1, at a certain time t, the neural network is capable of predicting the changes in vehicle state variables and thus the new state of the vehicle at a Δ t n v = 10 ms later time. This is a nice result, but the final aim of the research is to predict several seconds of vehicle motion as stated in Section 1.2. To enable this, an iterative calculation is necessary, where the neural network acts in a feedback loop. In this loop, the estimation of the new state at t + Δ t n v is fed back to the input of the neural network to predict the new state at t + 2 Δ t n v , and this goes on for the whole period of the simulation. Depending on the I/O variant, it may also be necessary to compute the yaw angle ψ n v (for V0) as well as the position coordinates x n v G and y n v G (for V0–2) with numerical integration, as they are not estimated directly by the neural network. State derivatives of the original dynamic model also need to be calculated numerically for all network variants. Initially, total simulation time t n v is split into equidistant steps of Δ t n v , denoting the resulting time series as t n v j with j = 0 t n v Δ t n v . The initial value of input vector X n v ( t n v 0 ) is assembled from initial values of vehicle inputs and states. Then, simulation happens in the following loop:
  •  Input vector X n v ( t n v j ) is applied to the neural network to compute output Y n v ( t n v j ) . In practice, input and output vectors must be scaled with the scaling vectors in Equations (59) and (60), but this is not reflected to in the equations for the sake of simplicity.
  •  Vehicle state variables for which estimations Δ ξ ( t n v j ) are available in the neural network output Y n v ( t n v j ) are calculated by
    ξ ( t n v j + 1 ) = ξ ( t n v j ) + Δ ξ ( t n v j )
    for general state ξ .
  •  For variant V0, yaw angle is calculated by numerical integration as
    ψ n v ( t n v j + 1 ) = Δ ψ ˙ n v ( t n v j ) + Δ ψ ˙ n v ( t n v j + 1 ) 2 Δ t n v .
  •  For variants V0–2, position coordinates are calculated by numerical integration as
    x n v G ( t n v j + 1 ) = x ˙ n v G ( t n v j ) + x ˙ n v G ( t n v j + 1 ) 2 Δ t n v ,
    y n v G ( t n v j + 1 ) = y ˙ n v G ( t n v j ) + y ˙ n v G ( t n v j + 1 ) 2 Δ t n v ,
    where velocities x ˙ n v G and y ˙ n v G are calculated from x ˙ n v V and y ˙ n v V by a rotation with − ψ n v .
  •  Vehicle state derivative variables for which estimations Δ ξ ( t n v j ) are available in the neural network output Y n v ( t n v j ) are estimated directly with differences
    ξ ˙ ( t n v j + 1 ) Δ ξ ( t n v j ) Δ t n v
    for general state ξ .
  •  Inertial accelerations in momentaneous vehicle frame are evaluated as
    x ¨ n v , I V ( t n v j + 1 ) = Δ x ˙ n v V ( t n v j ) Δ t n v y ˙ n v V ( t n v j ) ψ ˙ n v ( t n v j ) ,
    y ¨ n v , I V ( t n v j + 1 ) = Δ y ˙ n v V ( t n v j ) Δ t n v + x ˙ n v V ( t n v j ) ψ ˙ n v ( t n v j ) ,
    to take the rotating frame of reference into account.
  •  Input vector of next step, X n v ( t n v j + 1 ) is assembled from vehicle inputs and results of Equation (62).
  •  Steps 1–7 are repeated until simulation is finished.
Accordingly, our neural-network-based vehicle model consists of the network itself, which can predict the state of the vehicle for 10 ms, and the feedback loop algorithm described above, which uses the network to provide simulation results for several seconds. The presented approach can provide all the outputs that are available when using the original dynamical model. It is important to mention that the results coming from the presented simulation loop differ from the output of the original dynamic model even when assuming that the neural network is providing a perfect regression fit. The reason for this difference is, on the one hand, that state variables in Equations (63)–(65) are calculated with the forward Euler method (compared to the more sophisticated ODE solution of the dynamic model) and also on a sub-sampled dataset. On the other hand, state-derivative variables in Equation (66) are estimated with numeric differences (instead of the dynamic equations) and on a sub-sampled dataset as well.

5. Simulation Results

This section presents the simulation results of the neural-network-based vehicle model described in Section 4. The evaluations and comparisons in this chapter were mainly made in MATLAB, which can utilize the trained neural networks from keras. First, an example of the regression fit of the standalone neural network is presented and analyzed. Then, a closed-loop vehicle motion simulation example is shown to give a picture of the performance of the proposed algorithm in terms of output signals. Finally, the performance of different variants is evaluated.

5.1. Regression Fit

Figure 6 shows the regression results of the trained neural network for a sequence of testing samples that are coming directly from the dynamic vehicle simulation without shuffling. The number of 10,000 samples is the equivalent of 10 s dynamic simulation with a sample rate of 1 ms. As the output of the neural network consists of the changes in states Δ ξ ( t ) , these values are proportional to the derivative values of the corresponding states ξ ˙ ( t ) . Please note that all outputs are normalized to the range of [−1, 1]. Accordingly, the selected sequence of samples contains a scenario with considerable acceleration and braking as well as moderate steering and has an intermediate complexity from a dynamics point of view. The estimation of the neural network fits well to the output samples. The estimation error is, in all cases, more than one order of magnitude smaller than the estimated signal itself. Overall variables are shown, the maximal estimation error is 0.0727, and the mean estimation error is 0.0196.
Table 2 shows the typical values of estimation errors for a trained neural network for the most important output variables. The notation EMAX stands for maximal absolute error, while MAE (Mean Absolute Error) is used conventionally. We can see the biggest estimation errors in the case of changes in wheel speeds and longitudinal slip values. This behavior is logical, since the piecewise linear travel velocity profile that is used for the input sample generation results in a square-shaped longitudinal acceleration (and wheel angular acceleration) signal with jumps (this can be seen in Figure 6 as well). Learning these jumps is complicated for the neural network. While EMAX values are very high for these variables, they are only reached for a minimal number of samples. As MAE values show, average estimation error remains very small even in these cases. In comparison, changes in lateral slip values are much slower since the clothoid transition segments between the circular arcs and straight sections enable lateral tire forces (and wheel slips) to build up gradually. Accordingly, corresponding EMAX values are much slower. In general, we can say that while the regression provided by the neural network is not perfect, it is sufficient to be used for short-term vehicle simulations presented in Section 5.2.

5.2. Prediction of Vehicle Motion

Figure 7 shows the performance of the neural network based vehicle motion simulation in the case of the most important state variables.
The selected scenario is a 10 s long part of the test dataset and has an average dynamical complexity with longitudinal acceleration reaching −4 m/s2 and lateral acceleration exceeding 2 m/s2. The output of the neural network based model is able to nicely reproduce the output of the original dynamic model. The maximum error of position estimation is below 60 cm, and the maximal yaw (heading) angle estimation error remains under 2 . Prediction error of longitudinal velocity does not exceed 0.03 m/s, while yaw rate prediction error is below 0.6 /s. Inertial accelerations are also calculated with a maximal error of 0.2 m/s2. The biggest error can be observed in the case of lateral velocity, where the neural-network-based solution occasionally has a large offset of 0.05 m/s. However, the importance of this state variable from the motion planning point of view is not as high as that of the other ones listed above. The results show that with the application of appropriate safety boundaries applied to the position of the vehicle, the output of the neural-network-based model can be used for motion prediction in the online optimization loop of trajectory planner algorithms.

5.3. Evaluation of Input–Output Concept

It is also important to investigate the estimation errors for the whole test dataset to get a complete picture of the proposed method’s performance. To find the best choice of variants V0–3, a comparison of these is also necessary. Figure 8 shows the EMAX (maximal absolute error) values calculated for the whole test dataset and all vehicle simulation output quantities in case of the different variants V0–3 considering a 3 s long simulation time. Figure 9 shows the same information considering 10 s long simulations. The values labeled with ODE represent the estimation error that is present even if we assume perfect neural network performance. For these data, the worst case, considering the V0 variant with the maximal number of variables obtained by numerical integration, is selected. Please note that a logarithmic scale is used for the axis of error values.
As expected, the magnitude of overall estimation error is growing with the simulation time. On one hand, the value of state variables that are available in the neural network output is calculated by a cumulative sum according to Equation (62). In this way, the estimation error of these values accumulates with the number of steps in the estimation loop. As this cumulative sum of previous network outputs is also used to calculate the input of the network, the error spreads further.
On the other hand, the error of numerical integration for state variables that are not part of the neural network output also increases with the number of integration steps. For the state derivative quantities, the estimation errors’ speed of growth with simulation length is much less, as these are calculated directly from the neural network output.
From comparing the different variants, it is interesting to observe that direct position estimation with the V3 network massively underperforms the other variants with the numerically integrated position in the case of 3 s simulation time. Still, this performance gap disappears in the case of 10 s simulation, as the integration error grows faster. Besides this finding, there is no elementary difference between the performance of different variants. On average, variant V2 performs the best with direct yaw angle estimation and numerical position integration. The maximal position error remains under 1.5 m, and the maximal yaw angle error does not exceed 4 for the complete test dataset. These results are not much worse than the guaranteed performance of fused GNSS (Global Navigation Satellite System), and INS (Inertial Navigation System) localization solutions for global positioning [37]. Naturally, the most significant deviations can be observed in the case of the scenarios that are the most dynamically demanding with the largest longitudinal and lateral accelerations. This meets expectations, since the behavior of the vehicle becomes strongly nonlinear while moving closer to the adhesion limits of the tire–road contact. This nonlinear behavior is then harder to estimate, also because the very high acceleration events are rare compared to the average situations in the simulated realistic driving scenarios. With appropriate safety margins on the position results, the neural-network-based model can be used for simulations of approximately 10 s. For feasibility supervision, the original dynamic model can be used at any time.
Another important aspect of our evaluation is runtime, since the main goal with the presented dynamic-model-based training is to provide faster simulations with the neural-network-based model than with the original one. Figure 10 shows the runtime of the dynamic model and the different neural-network-based variants as to how many times faster they are evaluated than real-time (a ratio of simulated time and runtime). Due to the same total neuron count, almost all variants have the same runtime. Small differences can be observed due to the different number of state variables that have to be calculated by numerical integration. The dynamic model provides better performance with longer simulations because the initialization overhead remains the same in all cases. With short simulation times, the neural network based model is more than two times faster than the original one. Still, the advantage is clearly visible for the total domain of intended usage.

6. Discussion

It is important to discuss the limitations and possible issues of the proposed model. The main use case for the presented method is short-term vehicle motion simulation, particularly for the application in optimization-based motion planning algorithms. Accordingly, the proposed model cannot provide accurate results for simulations longer than approximately 10 s, as the regression error of the neural network is propagated inside the simulation loop.
The learning dataset comes from vehicle dynamics simulations with a planar single track model, which we would like to replace with the neural network based model. This dynamic model provides plausible results in the overwhelming majority of driving scenarios that happen on public roads. However, it also has some important limitations. Vertical dynamic effects such as road unevenness or load transitions due to road slope are not considered. Furthermore, scenarios where the friction conditions are important at all four wheels, such as when the left and right side of the vehicle meets with different road surface, cannot be simulated. The neural-network-based model will accordingly inherit the same limitations.
The driving maneuvers that were used to generate learning data also restrict the capabilities of the trained neural network. Because of this, a great emphasis is put on the definition of realistic random scenarios, which involve calm constant velocity parts and dynamically demanding high acceleration sections as well. However, the training maneuvers do not include parts where the vehicle is sliding or drifting or where the wheels are spinning or locking completely. This means that the neural-network-based model also cannot be expected to provide sufficient precision in such scenarios. The number of learning data is selected in a sense that the length of the resulting training process is feasible for experimenting. To increase the robustness of the proposed model, a final training with even more learning data could be performed as well in the future.

7. Conclusions and Future Work

This paper presents a novel method for short-term (≤10 s) vehicle motion simulation with an artificial neural-network-based approach. Firstly, learning samples are generated based on a classical nonlinear vehicle model for a dynamically diverse set of driving maneuvers. Reference data of these driving maneuvers are created by a numerical motion planning algorithm based on the assignment of piecewise linear travel velocity and curvature profiles similar to public road designs. The input of the trajectory planner is computed randomly to ensure that the resulting motions are realistic and contain demanding high-acceleration cases. Supervised learning techniques are then used to train the fully connected deep neural network to estimate a future state of the vehicle on the basis of its current state and driver inputs. The state variables that are not present in the output of the neural network are subsequently calculated by numerical integration. This algorithm is later used in a feedback loop to simulate the motion of the vehicle over time, where the output of the network is used to calculate its input for the next time step. For short-term simulations, the resulting neural-network based vehicle simulation algorithm is capable of fully replacing the classical dynamic model while being considerably faster. This speed gain can be especially useful in the online optimization loop of dynamically feasible optimal motion planner algorithms, where the required duration of simulations is typically inside the range where the new approach delivers plausible results. In this application, supervision of the neural-network-based results is possible by a one-time execution of the dynamic model.
The proposed algorithms are naturally not perfect. Investigation of the usage of different neural network architectures like cascade neural networks or recurrent neural networks like LSTM (Long Short-Term Memory) to estimate future vehicle state(s) to reach better regression performance would enable longer simulation times; this is a natural extension of the presented work. Another interesting future direction could be the application of transfer learning to adapt the presented model to changing vehicle parameters and friction conditions. As a next step towards a measurement-based training, sensor noises and errors could also be added to the perfect simulation data to examine their effect on the performance of the model. Training the neural networks based on real vehicle measurements afterwards is also an exciting opportunity to provide even more realistic simulations.

Author Contributions

Conceptualization, T.B. and F.H.; methodology, P.G. and F.H.; software, F.H.; validation, T.B and, P.G.; resources, P.G. and T.B.; writing—original draft preparation, F.H. and T.B.; writing—review and editing, P.G.; visualization, F.H. and T.B.; supervision, P.G.; funding acquisition, P.G. All authors have read and agreed to the published version of the manuscript.

Funding

The research was supported by the Ministry of Innovation and Technology NRDI Office within the framework of the Autonomous Systems National Laboratory Program. The research was also supported by the Hungarian Government and co-financed by the European Social Fund through the project “Talent management in autonomous vehicle control technologies” (EFOP-3.6.3-VEKOP-16-2017-00001).

Data Availability Statement

The data and source is available at the authors.

Conflicts of Interest

The authors declare no conflict of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript; or in the decision to publish the results.

Abbreviations

The following abbreviations and notations are used in this manuscript:
DDPGDeep Deterministic Policy Gradient
I/OInput–Output
JSONJavaScript Object Notation
MCTSMonte Carlo Tree Search
MAEMean Absolute Error
MPCModel Predictive Control
NWUNorth West Up
ODEOrdinary Differential Equation
PBDPosition Based Dynamics
PCAPrincipal Component Analysis
RBFNNRadial Basis Function Neural Network
ReLURectified Linear Unit
SELUScaled Exponential Linear Unit
SMCSliding Mode Control
Nomenclature
γ [ x / y ] G Dynamic quantity in inertial earth-fixed north-west-up coordinate system
γ [ x / y ] V Dynamic quantity in rotating vehicle-fixed forward-left-up coordinate system
γ [ f / r ] , [ x / y ] W Dynamic quantity in rotating front or rear wheel-fixed forward-left-up coordinate system
M d Driving torque (non-negative) [Nm]
M b Braking torque (non-negative) [Nm]
δ s w Steering wheel angle [rad]
x v G , y v G Position of vehicle center of gravity in x (north), and y (west) directions in earth-fixed coordinate system [m]
x ˙ v G , y ˙ v G Velocity of vehicle center of gravity in x (north), and y (west) directions in earth-fixed coordinate system [m/s]
x ¨ v G , y ¨ v G Acceleration of vehicle center of gravity in x (north), and y (west) directions in earth-fixed coordinate system [m/s2]
x ˙ v V , y ˙ v V Velocity of vehicle center of gravity in x (forward) and y (left) directions in vehicle-fixed coordinate system [m/s]
x ¨ v , I V , y ¨ v , I V Inertial acceleration of vehicle center of gravity in x (forward) and y (left) directions in instantaneous vehicle-fixed coordinate system [m/s2]
ψ v Yaw angle (rotation angle around up axis) in earth-fixed coordinate system [rad]
ψ ˙ v Yaw rate (angular velocity in z (up) direction) of vehicle in vehicle-fixed coordinate system [rad/s]
ψ ¨ v Yaw acceleration (angular acceleration in z (up) direction) of vehicle in vehicle-fixed coordinate system [rad/s2]
ρ [ f / r ] Turning angle of front and rear wheels [rad]
ρ ˙ [ f / r ] Angular velocity of front and rear wheels [rad/s]
ρ ¨ [ f / r ] Angular acceleration of front and rear wheels [rad/s2]
s [ f / r ] , [ x / y ] Slips of front and rear wheels in x (longitudinal) and y (lateral) direction
s ˙ [ f / r ] , [ x / y ] Slip derivatives of front and rear wheels in longitudinal (x) and lateral (y) direction [1/s]
δ f Steering angle of front wheel [rad]
δ ˙ f Steering angle derivative of front wheel [rad/s]
F [ f / r ] a , [ x / y ] G Acting tire forces of front and rear wheels in x (north) and y (west) directions in earth-fixed coordinate system [N]
F [ f / r ] a , [ x / y ] V Acting tire forces of front and rear wheels in x (forward) and y (left) directions in vehicle-fixed coordinate system [N]
F [ f / r ] a , [ x / y ] W Acting tire forces of front and rear wheels in x (longitudinal), and y (lateral) directions in wheel-fixed coordinate systems [N]
F [ f / r ] n , [ x / y ] W Tire forces of front and rear wheels in x (longitudinal), and y (lateral) directions in wheel-fixed coordinate systems in case of pure longitudinal or lateral slip [N]
F [ f / r ] c , [ x / y ] W Tire forces of front and rear wheels in x (longitudinal), and y (lateral) directions in wheel-fixed coordinate systems in case of combined slip [N]
F d , [ x / y ] G Aerodynamic drag forces in x (north) and y (west) directions in earth-fixed coordinate system [N]
F d , [ x / y ] V Aerodynamic drag forces in x (forward) and y (left) directions in vehicle-fixed coordinate system [N]
F [ f / r ] , z V Tire load forces in z (up) direction in vehicle-fixed coordinate system [N]
M [ f / r ] , d Driving torques of front and rear wheels [Nm]
M [ f / r ] , b , M [ f / r ] , b a Intended and acting braking torques of front and rear wheels [Nm]
M [ f / r ] , r r , M [ f / r ] , r r a Calculated and acting rolling resistance torques of front and rear wheels [Nm]
c [ f / r ] , M Torque distribution factor to front and rear wheels
x ˙ [ f / r ] W , y ˙ [ f / r ] W Center point velocities of front and rear wheels in x (longitudinal) and y (lateral) directions in wheel-fixed coordinate system [m/s]
x ˙ [ f / r ] V , y ˙ [ f / r ] V Center point velocities of front and rear wheels in x (forward) and y (left) directions in vehicle-fixed coordinate system [m/s]
v [ f / r ] , r Rolling velocity of front and rear wheels [m/s]
s [ f / r ] d , [ x / y ] Damped slips of front and rear wheels in x (longitudinal) and y (lateral) direction
K [ f / r ] , [ x / y ] Slip stiffness of front and rear wheels in x (longitudinal) and y (lateral) direction
k [ f / r ] d , x Actual longitudinal slip damping factor
l [ f / r ] a , [ x / y ] Slip dependent actual relaxation lengths of front and rear tires in x (longitudinal) and y (lateral) direction [m]
X v State vector of vehicle
X ˙ v Derivative of vehicle state vector
m v Total mass of vehicle [kg]
θ v , z Moment of inertia of the vehicle around z (up) axis [kgm2]
h v Center of gravity height of the vehicle [m]
l v , [ f / r ] Horizontal distance of vehicle center of gravity and the front and rear axes [m]
A v , f Frontal area of the vehicle [m2]
c v , d Aerodynamic drag coefficient of the vehicle
ρ a Density of air [kg/m3]
θ [ f / r ] Moment of inertia of the front and rear wheels [kgm2]
r [ f / r ] Radii of the front and rear wheels [m]
v b a , 0 , v b a Minimal and actual rolling velocity at which braking torque shall be fully applied [m/s]
k v b a Braking torque dependent factor for v b a [1/Ns]
A [ f / r ] , r r , B [ f / r ] , r r , C [ f / r ] , r r Rolling resistance coefficients [1], [s/m], [s2/m2]
v r r a Rolling velocity at which rolling resistance torque shall be fully applied [m/s]
D [ f / r ] , [ x / y ] Maximum values of Magic Formula for front and rear wheels in x (longitudinal) and y (lateral) direction
C [ f / r ] , [ x / y ] Shape factors of Magic Formula for front and rear wheels in x (longitudinal) and y (lateral) direction
B [ f / r ] , [ x / y ] Stiffness factors of Magic Formula for front and rear wheels in x (longitudinal) and y (lateral) direction
E [ f / r ] , [ x / y ] Curvature factors of Magic Formula for front and rear wheels in x (longitudinal) and y (lateral) direction
μ [ f / r ] Coefficient of friction at front and rear wheels
k [ f / r ] , x Initial longitudinal slip damping factor
v s d Rolling velocity at which slip damping should switch off
s d a Minimal value of wheels slips at which superposition of forces shall first be considered
l [ f / r ] , [ x / y ] , l [ f / r ] m , [ x / y ] Initial and minimal relaxation lengths of front and rear tires in x (longitudinal) and y (lateral) direction [m]
k s Steering ratio
T s Settling time of steering mechanism
Δ t v Sample time of vehicle model solution [s]
t v Time of vehicle motion simulation [s]
σ p , σ p i Arc length, arc length knot points [m]
κ p , κ p i Curvature of path, curvature profile knot points [1/m]
x ˙ p , x ˙ p i Travel speed along path, travel speed profile knot points [m/s]
N p i Number of knot points specified for curvature and travel speed profile
Δ t p i Time needed to travel along path section i [s]
Δ σ p i Length of path section i [m]
x ˙ ˜ p i Average travel speed of path section i [m/s]
t p , t p i Travel time along path, time needed to reach end of path section i [s]
x ¨ p , x ¨ p i Longitudinal acceleration along path, and at path section i [m/s2]
ψ ˙ p , ψ ˙ p j Yaw rate (angular velocity in z direction) along path, yaw rate output samples [rad/s]
y ¨ p Centripetal acceleration along path [m/s2]
ψ p , ψ p , 0 , ψ p j Yaw angle (rotation angle around up axis) along path and initially, yaw angle output samples [rad]
x p , x p , 0 , x p j y p , y p , 0 , y p j Position in x (north), and y (west) directions in earth-fixed coordinate system along path and initially, position output samples [m]
σ p , s Arc length resolution for numeric calculations [m]
N p j Number of reference trajectory points
N r Number of road segments
x ˙ p , [ m i n / m a x ] Maximal and minimal allowed travel speed [m/s]
y ¨ p , m a x Maximal allowed centripetal acceleration [m/s2]
r p i Radius of path section i [m]
r p , m i n i Minimal allowed radius for path section i [m]
c r , m i n Multiplier factor for minimal allowed radii
c c , [ m i n / m a x ] Multiplier factor path section length in proportion to circumference
c s Proportion of straight sections compared to curved sections
c t Proportion of transition section length to normal section length
Δ t n v Prediction time of neural network based vehicle model [s]
ξ General state variable
Δ ξ Change of state variable in Δ t n v time
X n v V A R Input vector of neural network variant VAR
Y n v V A R , Y n v i Output vector of neural network variant VAR. Element of output vector
I n v t r , I n v t t Matrices of training and testing input samples
O n v t r , O n v t t Matrices of training and testing output samples
N v t r Total number of vehicle simulation samples generated for training
c X n v Vector of input scales (maximum absolute value of each variable in X n v )
c Y n v Vector of output scales (maximum absolute value of each variable in Y n v )
L n v Training loss
n Y n v Number of elements of output vector Y n v
w L n v , w L n v i Weighting vector for squared error in estimation of Y n v . Element of weighting vector
Y ^ n v , Y ^ n v i Estimation of Y n v by the neural network. Element of estimation vector
t n v , t n v j Time of neural network based vehicle simulation. Time at simulation step j [s]
ψ n v Yaw angle (rotation around up axis) in earth-fixed coordinate system. Computed by neural network based vehicle model [rad]
x n v G , y n v G Position of vehicle center of gravity in x (north), and y (west) directions in earth-fixed coordinate system [m]. Computed by neural network based vehicle model
x ¨ n v , I V , y ¨ n v , I V Inertial acceleration of vehicle center of gravity in x (forward) and y (left) directions in instantaneous vehicle-fixed coordinate system [m/s2]. Computed by neural network based vehicle model
E M A X Maximum absolute estimation error of neural network
τ r Run time as factor to real-time speed

References

  1. Watzenig, D.; Horn, M. Automated Driving: Safer and More Efficient Future Driving; Springer: Berlin/Heidelberg, Germany, 2016. [Google Scholar]
  2. Tettamanti, T.; Varga, I.; Szalay, Z. Impacts of Autonomous Cars from a Traffic Engineering Perspective. Period. Polytech. Transp. Eng. 2016, 44, 244–250. [Google Scholar] [CrossRef] [Green Version]
  3. Barsi, Á.; Csepinszky, A.; Lógó, J.; Krausz, N.; Potó, V. The Role of Maps in Autonomous Driving Simulations. Period. Polytech. Transp. Eng. 2020, 48, 363–368. [Google Scholar] [CrossRef]
  4. Colan, J.; Nakanishi, J.; Aoyama, T.; Hasegawa, Y. Optimization-Based Constrained Trajectory Generation for Robot-Assisted Stitching in Endonasal Surgery. Robotics 2021, 10, 27. [Google Scholar] [CrossRef]
  5. Beschi, M.; Mutti, S.; Nicola, G.; Faroni, M.; Magnoni, P.; Villagrossi, E.; Pedrocchi, N. Optimal Robot Motion Planning of Redundant Robots in Machining and Additive Manufacturing Applications. Electronics 2019, 8, 1437. [Google Scholar] [CrossRef] [Green Version]
  6. Zhang, X.; Ming, Z. Trajectory Planning and Optimization for a Par4 Parallel Robot Based on Energy Consumption. Appl. Sci. 2019, 9, 2770. [Google Scholar] [CrossRef] [Green Version]
  7. Howard, T.M.; Kelly, A. Optimal rough terrain trajectory generation for wheeled mobile robots. Int. J. Robot. Res. 2007, 26, 141–166. [Google Scholar] [CrossRef]
  8. Urmson, C.; Anhalt, J.; Bagnell, D.; Baker, C.; Bittner, R.; Clark, M.N.; Dolan, J.; Duggins, D.; Galatali, T.; Ferguson, D.; et al. Autonomous driving in urban environments: Boss and the urban challenge. J. Field Robot. 2008, 25, 425–466. [Google Scholar] [CrossRef] [Green Version]
  9. Ajanovic, Z.; Lacevic, B.; Shyrokau, B.; Stolz, M.; Horn, M. Search-Based Optimal Motion Planning for Automated Driving. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 4523–4530. [Google Scholar] [CrossRef] [Green Version]
  10. Diachuk, M.; Easa, S.M.; Bannis, J. Path and Control Planning for Autonomous Vehicles in Restricted Space and Low Speed. Infrastructures 2020, 5, 42. [Google Scholar] [CrossRef]
  11. Hegedus, F.; Bécsi, T.; Aradi, S.; Szalay, Z.; Gáspár, P. Real-time optimal motion planning for automated road vehicles. In Proceedings of the 21th IFAC World Congress, Berlin, Germany, 12–17 July 2020; pp. 15856–15861. [Google Scholar]
  12. Bender, J.; Müller, M.; Macklin, M. Position-Based Simulation Methods in Computer Graphics. Eurographics 2015. [Google Scholar] [CrossRef]
  13. Müller, M.; Heidelberger, B.; Hennix, M.; Ratcliff, J. Position based dynamics. J. Vis. Commun. Image Represent. 2007, 18, 109–118. [Google Scholar] [CrossRef] [Green Version]
  14. Harmon, D.; Zorin, D. Subspace integration with local deformations. ACM Trans. Graph. (TOG) 2013, 32, 1–10. [Google Scholar] [CrossRef]
  15. von Radziewsky, P.; Eisemann, E.; Seidel, H.P.; Hildebrandt, K. Optimized subspaces for deformation-based modeling and shape interpolation. Comput. Graph. 2016, 58, 128–138. [Google Scholar] [CrossRef]
  16. Xu, W.; Umetani, N.; Chao, Q.; Mao, J.; Jin, X.; Tong, X. Sensitivity-optimized rigging for example-based real-time clothing synthesis. ACM Trans. Graph. 2014, 33, 107:1–107:11. [Google Scholar] [CrossRef]
  17. Luo, R.; Shao, T.; Wang, H.; Xu, W.; Chen, X.; Zhou, K.; Yang, Y. NNWarp: Neural network-based nonlinear deformation. IEEE Trans. Vis. Comput. Graph. 2018, 26, 1745–1759. [Google Scholar] [CrossRef] [Green Version]
  18. Holden, D.; Duong, B.C.; Datta, S.; Nowrouzezahrai, D. Subspace neural physics: Fast data-driven interactive simulation. In Proceedings of the 18th annual ACM SIGGRAPH/Eurographics Symposium on Computer Animation, Los Angeles, CA, USA, 26–28 July 2019; pp. 1–12. [Google Scholar]
  19. Hu, S.; d’Ambrosio, S.; Finesso, R.; Manelli, A.; Marzano, M.R.; Mittica, A.; Ventura, L.; Wang, H.; Wang, Y. Comparison of Physics-Based, Semi-Empirical and Neural Network-Based Models for Model-Based Combustion Control in a 3.0 L Diesel Engine. Energies 2019, 12, 3423. [Google Scholar] [CrossRef] [Green Version]
  20. Guarneri, P.; Rocca, G.; Gobbi, M. A Neural-Network-Based Model for the Dynamic Simulation of the Tire/Suspension System While Traversing Road Irregularities. IEEE Trans. Neural Netw. 2008, 19, 1549–1563. [Google Scholar] [CrossRef]
  21. Liu, X.; Hu, D.; Xiao, J.; Hu, J. Modeling and simulation on movement of air cushion vehicle based on neural network. In Proceedings of the 2017 2nd International Conference on Robotics and Automation Engineering (ICRAE), Shanghai, China, 29–31 December 2017; pp. 513–516. [Google Scholar]
  22. Swain, S.K.; Rath, J.J.; Veluvolu, K.C. Neural Network Based Robust Lateral Control for an Autonomous Vehicle. Electronics 2021, 10, 510. [Google Scholar] [CrossRef]
  23. He, Z.; Nie, L.; Yin, Z.; Huang, S. A two-layer controller for lateral path tracking control of autonomous vehicles. Sensors 2020, 20, 3689. [Google Scholar] [CrossRef]
  24. Song, S.; Chen, H.; Sun, H.; Liu, M. Data Efficient Reinforcement Learning for Integrated Lateral Planning and Control in Automated Parking System. Sensors 2020, 20, 7297. [Google Scholar] [CrossRef]
  25. Hu, H.; Lu, Z.; Wang, Q.; Zheng, C. End-to-End Automated Lane-Change Maneuvering Considering Driving Style Using a Deep Deterministic Policy Gradient Algorithm. Sensors 2020, 20, 5443. [Google Scholar] [CrossRef]
  26. Hegedüs, F.; Bécsi, T.; Aradi, S.; Gáspár, P. Motion Planning for Highly Automated Road Vehicles with a Hybrid Approach Using Nonlinear Optimization and Artificial Neural Networks. Stroj. Vestn. J. Mech. Eng. 2019, 65, 148–160. [Google Scholar] [CrossRef]
  27. Kovári, B.; Hegedüs, F.; Bécsi, T. Design of a Reinforcement Learning-Based Lane Keeping Planning Agent for Automated Vehicles. Appl. Sci. 2020, 10, 7171. [Google Scholar] [CrossRef]
  28. Hegedüs, F.; Bécsi, T.; Aradi, S.; Gáspár, P. Model based trajectory planning for highly automated road vehicles. IFAC-PapersOnLine 2017, 50, 6958–6964. [Google Scholar] [CrossRef]
  29. Schramm, D.; Hiller, M.; Bardini, R. Vehicle Dynamics; Springer: Berlin/Heidelberg, Germany, 2014. [Google Scholar]
  30. Luhua, Z.; Qinggui, C.; Yushan, L.; Naixiu, G. An optimization technique of braking force distribution coefficient for truck. In Proceedings of the 2011 International Conference on Transportation, Mechanical, and Electrical Engineering (TMEE), Changchun, China, 16–18 December 2011; pp. 1784–1787. [Google Scholar]
  31. Hall, D.E.; Moreland, J.C. Fundamentals of rolling resistance. Rubber Chem. Technol. 2001, 74, 525–539. [Google Scholar] [CrossRef]
  32. Pacejka, H.B. Tire and Vehicle Dynamics, 3rd ed.; Butterworth-Heinemann: Oxford, UK, 2012; pp. 355–401. [Google Scholar] [CrossRef]
  33. Snider, J.M. Automatic Steering Methods for Autonomous Automobile Path Tracking; CMU-RITR; Robotics Institute: Pittsburgh, PA, USA, 2009. [Google Scholar]
  34. Cantisani, G.; Del Serrone, G. Procedure for the Identification of Existing Roads Alignment from Georeferenced Points Database. Infrastructures 2021, 6, 2. [Google Scholar] [CrossRef]
  35. Parlangeli, G.; Ostuni, L.; Mancarella, L.; Indiveri, G. A motion planning algorithm for smooth paths of bounded curvature and curvature derivative. In Proceedings of the 2009 17th Mediterranean Conference on Control and Automation, Thessaloniki, Greece, 24–26 June 2009; pp. 73–78. [Google Scholar]
  36. Kingma, D.P.; Ba, J. Adam: A method for stochastic optimization. arXiv 2014, arXiv:1412.6980. [Google Scholar]
  37. Dong, Y.; Wang, D.; Zhang, L.; Li, Q.; Wu, J. Tightly Coupled GNSS/INS Integration with Robust Sequential Kalman Filter for Accurate Vehicular Navigation. Sensors 2020, 20, 561. [Google Scholar] [CrossRef] [Green Version]
Figure 1. Progress of presented research.
Figure 1. Progress of presented research.
Electronics 10 00928 g001
Figure 2. Nonlinear single track vehicle model.
Figure 2. Nonlinear single track vehicle model.
Electronics 10 00928 g002
Figure 3. Motion planning input and output.
Figure 3. Motion planning input and output.
Electronics 10 00928 g003
Figure 4. Random trajectories.
Figure 4. Random trajectories.
Electronics 10 00928 g004
Figure 5. Learning progress of neural network.
Figure 5. Learning progress of neural network.
Electronics 10 00928 g005
Figure 6. Regression fit of the trained neural network.
Figure 6. Regression fit of the trained neural network.
Electronics 10 00928 g006
Figure 7. Motion prediction with trained neural network.
Figure 7. Motion prediction with trained neural network.
Electronics 10 00928 g007
Figure 8. Maximum estimation error of neural network based models for 3 s simulation.
Figure 8. Maximum estimation error of neural network based models for 3 s simulation.
Electronics 10 00928 g008
Figure 9. Maximum estimation error of neural network based models for 10 s simulation.
Figure 9. Maximum estimation error of neural network based models for 10 s simulation.
Electronics 10 00928 g009
Figure 10. Runtime of neural-network-based models.
Figure 10. Runtime of neural-network-based models.
Electronics 10 00928 g010
Table 1. Neural network layouts.
Table 1. Neural network layouts.
NameLayout
n256l3v1[64, 128, 64]
n256l3v2[32, 192, 32]
n256l4v1[32, 96, 96, 32]
n256l4v2[64, 128, 128, 64]
Table 2. Regression fit error statistic of a typical trained neural network.
Table 2. Regression fit error statistic of a typical trained neural network.
VariableEMAXMAEVariableEMAXMAE
× 10 2 × 10 2
Δ x ˙ v V ( t ) 0.170430.08441 Δ s f , x ( t ) 0.930730.09424
Δ y ˙ v V ( t ) 0.167930.07394 Δ s f , y ( t ) 0.163740.08827
Δ ψ ˙ v ( t ) 0.245120.08250 Δ s r , x ( t ) 0.429430.08377
Δ ρ ˙ f ( t ) 0.824520.15126 Δ s r , y ( t ) 0.133170.05913
Δ ρ ˙ r ( t ) 0.512420.14104 Δ δ f ( t ) 0.158710.04865
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Hegedüs, F.; Gáspár, P.; Bécsi, T. Fast Motion Model of Road Vehicles with Artificial Neural Networks. Electronics 2021, 10, 928. https://doi.org/10.3390/electronics10080928

AMA Style

Hegedüs F, Gáspár P, Bécsi T. Fast Motion Model of Road Vehicles with Artificial Neural Networks. Electronics. 2021; 10(8):928. https://doi.org/10.3390/electronics10080928

Chicago/Turabian Style

Hegedüs, Ferenc, Péter Gáspár, and Tamás Bécsi. 2021. "Fast Motion Model of Road Vehicles with Artificial Neural Networks" Electronics 10, no. 8: 928. https://doi.org/10.3390/electronics10080928

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop