Get 20M+ Full-Text Papers For Less Than $1.50/day. Start a 14-Day Trial for You or Your Team.

Learn More →

Planning flexible and smooth paths for lane‐changing manoeuvres of autonomous vehicles

Planning flexible and smooth paths for lane‐changing manoeuvres of autonomous vehicles INTRODUCTIONAutonomous vehicle technology has received much attention recently. Autonomous vehicles can improve traffic safety, occupant comfort, and convenience in daily life. Advanced driver assistance systems, such as lane‐keeping assistance, adaptive cruise control (ACC), and automatic emergency braking, are already available in production vehicles. Technologies for lane‐changing manoeuvres of autonomous vehicles have also proven very useful and have been widely studied. The lane‐changing manoeuvres can be considered a component that involves both longitudinal and lateral control [1]. The longitudinal control ensures that the vehicle maintains a safe distance from surrounding vehicles. This aspect can be fulfilled by an ACC. The lateral control causes the vehicle to move laterally to the target lane. Some lateral control methods based on model‐predictive control do not require a planned path [2, 4], but most lateral control methods require a target path for tracking. An appropriate lane‐changing path can also function as a good reference input for model‐predictive control. Therefore, a lane‐changing path or a lane‐changing path planning method is a very important part of the lane change.Motion planning techniques and ideal vehicle lane‐changing trajectories have been summarised and compared in the literature [5, 6]. Motion planning techniques are divided into global and local planning and can be classified into four groups: graph search, sampling, interpolating, and numerical optimisation. Interpolating and graph search are the two main algorithms applied in real‐world implementations. Lane‐changing path planning problems are an aspect of local planning and can be solved by interpolation. The desired vehicle trajectories in lane changes are evaluated from the length, curvature, curvature derivatives, and critical speed [6]. And the lane‐changing paths should also be personalised [7, 8], safety, collision avoidance, and stabilisation [9–11]. The acceptance of the driver has also to be considered [12–14]. Therefore, it is very important to predict the entire lane‐changing path [15]. It can evaluate the information above before performing the lane change.The line and circle curve planner [16] was first considered because of its low computational cost. However, it cannot be accepted because a sudden trajectory change from a line to a circle will induce an instantaneous change in the lateral acceleration, causing an infinite jerk. The polynomial curve planner is also a good choice with low computational cost [17, 18]. However, as the design parameters of the path increase, the degree of the polynomial increases, making it increasingly difficult to solve the coefficients. Moreover, if the start and target configurations are fixed, it is difficult to adjust the middle section of the polynomial path. Bezier curves and B‐splines are suitable for obtaining smooth paths [19–21], but it is not easy to calculate the curvature and heading of the path when the maximum limits of the lateral acceleration and jerk are considered.Clothoids are a natural choice for lane‐changing path planning because they have already been applied in road design [22, 23] and have the advantage of linearly changing curvature. Thus, a path planned by clothoids is easy to follow and results in higher tracking accuracy. Unfortunately, clothoids are defined in terms of Fresnel integrals [24], making clothoid‐form path solutions difficult to be achieved analytically. Scheuer and Fraichard created a subset of clothoid‐based paths called bi‐elementary paths, for which closed‐form expressions exist to obtain solutions [25]. Funke and Christian Gerdes applied bi‐elementary paths to design lane‐changing trajectories for automated vehicles and achieved good results [26]. However, it is not flexible and only suitable for planning initial lane‐changing path from straight to straight. In other words, the planned path should be zero heading and curvature at the start and end, which is not suitable for real‐time changing traffic environment.To solve these problems, this paper proposes a new lane‐changing path planning algorithm. Clothoid and arc curves are superimposed on the bi‐elementary path based on longitudinal distance, making the path planning method sufficiently flexible to adapt to real‐time changing traffic environment. The proposed method also maintains a continuous curvature and heading under path planning or re‐planning and is no longer restricted to zero heading and curvature at the start and end. When the start and target configurations are fixed, different shapes of the lane‐changing path can be generated for different personal habits. A lookup table method is applied, and an appropriate accuracy is used for the clothoid expression, allowing the algorithm to run on the embedded hardware platforms of production vehicles. Finally, a tracking controller suitable for the path planning method proposed in this work is designed for a better tracking accuracy.The remainder of this paper is organised as follows. In Section 2, the framework of a lateral lane‐changing control system and the main parameters are introduced. Lane‐changing path planning and tracking methods are introduced in Section 3. In Section 4, simulation comparison and experimental results are reported to demonstrate the feasibility of the proposed lane‐changing path planning method. Finally, the conclusions of this paper are summarised in Section 5.FRAMEWORK DESCRIPTIONThis section introduces the framework of the lateral lane‐changing control system used in this paper. The framework is depicted in Figure 1. The longitudinal control is not included because this paper studies lateral lane‐changing path planning based on decoupled lane change. The longitudinal control aspect can be served by an ACC to maintain a safe distance with surrounding vehicles. The changes in longitudinal speed under the limits will not affect the framework. The limits are given by the maximum curvature of the planned lane‐changing path [26], and the lateral tracking controller designed is adaptive speed. The framework leverages path planning and lateral tracking to perform a lateral lane‐changing task. First, a lane‐changing intention is generated based on vehicle status and environmental information. Second, the start configuration is generated based on the vehicle status and target configuration is generated based on the target lane and comfort or obstacles restriction. Then, a lane‐changing path is generated by the method proposed in this work based on the configurations, after which the generated path is checked. If the path is not collision‐free, the configurations and lane‐changing path are regenerated. Finally, the lateral tracking controller generates a steering wheel angle command for the electric power steering system (EPS) with an angle interface based on the lane‐changing path and vehicle velocity.1FIGUREThe diagram of the lateral lane‐changing control systemThe main parameters for the generation of a lane‐changing path and the lateral tracking controller are shown in Table 1.1TABLEThe main parameters for generating a lane‐changing path and the lateral tracking controllerSymbolDescriptionUnitsxLongitudinal distancemyLateral displacementmφHeadingradκCurvature1/mσSharpness1/m2λArc length fraction1DFraction for solving the length of an elementary path1LsLength of a clothoid curvemvhVehicle velocitym/sKusUnder‐steer gradients2/mLhVehicle wheelbasemKgaLateral acceleration steady‐state gainm/s2kp1Lateral displacement proportional gain1kp2Heading proportional gain1ki2Heading integral gain1LANE‐CHANGING PATH PLANNING AND TRACKINGThe bi‐elementary path for lane‐changing planning and its real‐time calculationA bi‐elementary path is composed of two elementary paths. An elementary path Π(l,κ) is constructed by two segments of clothiods, as shown in Figure 2. The first clothoid is named as ‘entry clothoid’ and the second clothoid is named as ‘exit clothoid’ [26]. The total length of the elementary path Π(l,κ) is described by l, and the path curvature profile k is a linear function of its arc length s, i.e., k(s)=σs, where σ is a real constant called the sharpness of the clothoid. Therefore, the path Π(l,κ) can be expressed as1k(s)=σs∀s∈[0,ll22]k(s)=σ(l−s)∀s∈[ll22,l].2FIGUREAn elementary path composed of two clothoidsThe curvature profile with a strictly positive σ is shown in Figure 3. Its curvature increases linearly from zero to a maximum of k(l/l22)=σl/σl22 and then decreases linearly back to zero. Obviously, this elementary path curvature is symmetric and the path is symmetric. The start and end configurations of the elementary path are q0(x0,y0,φ0) and ql(xl,yl,φl), respectively. Consequently, the change of heading Δψ from the start configuration to the end configuration can be expressed as2Δψ=φl−φ0=2θ=2tan−1yl−y0xl−x0.3FIGUREThe curvature profile of the elementary pathTo reduce the maximum curvature, an arc is inserted into the elementary paths, as shown in Figure 4. However, this increases the computational complexity of an elementary path length, which is expressed as [26]3l=dDΔψ,λwhere dis the distance between the start and end points of an elementary path and D(Δψ,λ)is a parameter from the geometry of a symmetric path given Δψ and λ. D(Δψ,λ) is expressed as4DΔψ,λ=2∫00.5cosfzdzwhere f(z) is given by5fz=2Δψ1+λz∀z∈0,λ22Δψ1−λ2−z2+z−λ24∀z∈λ2,12and λ∈[0,1] is the inserted arc length fraction.4FIGUREAn elementary path with an arcTo simplify the calculation of the parameter D(Δψ,λ) for embedded platforms, a lookup table method is designed. Because the change of heading Δψ is small and bounded during the lane change, and the parameter D(Δψ,λ) monotonically decreases with |Δψ| and increases with λ, a lookup table method is feasible. The table is shown as Figure 5. The parameter D(Δψ,λ) is calculated online by lookup table through the input of |Δψ| and λ.5FIGUREThe lookup table of the parameter D(Δψ,λ)Two elementary paths comprise a bi‐elementary path, as shown in Figure 6. The start configuration is qs(xs,ys,φs) and the target configuration is qt(xt,yt,φt). An intermediate configuration qi(xi,yi,φi) is needed to connect qs(xs,ys,φs) and qt(xt,yt,φt) with two elementary paths. The candidate intermediate configurations are given in [27].6FIGURETwo bi‐elementary paths of parallel and non‐parallel configurationsIf the orientations of qsand qtare parallel, the intermediate configurations qi1(xi1,yi1,φi1) are located on a line passing through qs and qt, as shown in Figure 6, which can be expressed as6(xi1−xs)(yi1−yt)=(xi1−xt)(yi1−ys).In contrast, when the orientations of qsand qtare not parallel, the intermediate configurations qi2(xi2,yi2,φi2) are located on a circle passing through qs and qt, as shown in Figure 6, which can be expressed as7(xi2−xs)(yi2−yt)−(xi2−xt)(yi2−ys)=(xi2−xs)(xi2−xt)+(yi2−ys)(yi2−yt)tan(φt−φs2).Clothoids are the basis of a bi‐elementary path. Therefore, the simpler the coordinate calculation of clothoids is, the more efficient the real‐time calculation is. A real‐time approximation of clothoids with a bounded error for a path planning application method was proposed in [28]. This method is based on lookup tables and improves the approximation of clothoids under large lengths. It requires storing large basic clothoids and using circular interpolation. For clothoids under small lengths, applying the two‐point analogue of Taylor expansions [29] to compute the clothoid coordinates is easier. The basic clothoids, which are the heading and the curvature, start with zero and are expressed as8xls=ls−ls540Rs2Ls2yls=ls36RsLs−ls7336Rs3Ls3φls=ls22RsLswhere ls is the length between the start point and any point in the clothoid, Ls is the total length of the clothoid, Rs is the radius at the end point of the clothoid, x(ls) and y(ls) are the coordinates of the clothoid in the Cartesian coordinate system, and φ(ls) is the heading in the Cartesian coordinate system.The clothoid curves whose initial orientations are non‐zero can be obtained by coordinate transformation from the basic clothoids:9XY=cosφs−sinφssinφscosφsxy.A flexible lane‐changing path planning methodNormally, a lane‐changing manoeuvre transitions a vehicle from one straight lane into another. In this circumstance, the vehicle's heading at the start and end of a lane change should be equal to zero. Furthermore, the curvatures at the start and end of a lane change are also zero. Bi‐elementary paths can satisfy these conditions, and for a straight lane, there is no problem with directly applying bi‐elementary paths for generating the initial lane‐changing paths. However, lane changes may also occur on a curved lane when the field of view is good and the lane curvature is small. Additionally, the lane‐changing paths also need to be re‐planned when the traffic environment changes. In both the above two cases, the curvatures at the start and end of the lane‐changing paths are non‐zero. Unfortunately, bi‐elementary paths are not flexible enough to adapt to these situations, and they also are unable to keep the curvature continuous when re‐planning.To avoid the restriction imposed by the requirement of the initial and end zero curvature condition, curvature information is introduced into the planning. The configuration is redefined as q(x,y,φ,κ), and extra curve paths are superimposed on the bi‐elementary path based on the longitudinal distance to make the curvature controllable. Based on different start curvature κs and target curvature κt conditions, it can be divided into three cases to superimpose the curve paths on the bi‐elementary path, as shown in Table 2.2TABLEConditions for superimposing curvesCaseConditionSuperimposed curve path1κs≠0,κt=0 or κs≠0,κt=0Clothoid2κs=κt,κs≠0,κt≠0Arc3κs≠κt,κs≠0,κt≠0Arc and clothoidFor all cases, the general planning process is described in Figure 7. Start and target configurations of the superimposed curve path s1 and the bi‐elementary path s2 are solved first, and then superimposed curve path s1 and bi‐elementary path s2 are planned. Paths s1 and s2 are superimposed together based on the longitudinal distance to obtain the final lane‐changing path.7FIGUREThe general planning process for all casesThe problem of the process is how to calculate the new configurations. For the first case, taking conditions κs≠0andκt=0 as example, φt1 is set to be zero in order to simplify the calculation; therefore, φt2 is equal to φt. yt1 and φs1 can be calculated by (8) and (9), because path s1 is a basic clothoid rotated 180°. φs2 is calculated by φs2=φs−φs1, and yt2 is calculated by yt2=yt−yt1. The planned lane‐changing path s, superimposed clothoid path s1 and bi‐elementary path s2 are shown in Figure 8. For the second case, φs1 is set to be zero in order to simplify the calculation, therefore φs2 is equal to φs. Because the arc path s1 is a circle curve and its constant curvature is set to be κs, yt1 can be calculated as10yt1=ys−signks1κs2−xt−xs2+1κs.8FIGURELane‐changing path planning of the first caseAnd φt1 can be calculated as11φt1=2arctanyt1xt−xs.Then, φt2 is calculated by φt2=φt−φt1, and yt2 is calculated by yt2=yt−yt1. The planned lane‐changing path s, superimposed arc path s1, and bi‐elementary path s2 are shown in Figure 9.9FIGURELane‐changing path planning of the second caseFor the third case, the configurations of the arc path are solved first as in the second case, and the only difference is that its constant curvature is set to be κt. The target lateral coordinate ytc and heading φtc of the arc path are calculated by (10) and (11). Therefore, the other configurations can be expressed as qso(xs,ys,φs,κs−κt) and qto(xt,yt−ytc,φt−φtc,0), and this is the same as the first case.The above method can keep the curvature continuous when re‐planning, and it adapts to non‐zero curvatures at the start and end. To minimise the maximum scalar value of the curvature of the lane‐changing path, the appropriate intermediate configuration must be determined. A bi‐elementary path has both a positive curvature peak and a negative curvature peak. Each curvature peak is the curvature peak of the elementary path, as shown in Figure 3. When the intermediate point moves in the candidate intermediate curve, one curvature peak scalar will increase and the other curvature peak scalar will decrease. There is an intermediate point that makes the two curvature peak scalars equal and minimum. The curvature peak scalar can be expressed as12κsmax=l2σ=4Dθdwhere σ is given byσ=4Δψl2 [26]. To characterise the relationship between the two curvature peak scalars, the parameter c is defined as13c=κs1maxκs2maxwhere κs1maxis the first curvature peak scalar and κs2max is the second curvature peak scalar. Here, c not only represents the relationship between the two curvature peak scalars, but also determines the shape of the planned path. Therefore, c is a shape characteristic parameter of the planned lane‐changing path. When c equals 1, the two curvature peak scalars are equal and minimal, which is the target in this paper. When c is greater than 1, the first curvature peak scalar is greater than the second curvature peak scalar and can be used to quickly generate the lateral acceleration and heading at the beginning of the lane change. When c is less than 1, the first curvature peak scalar is less than the second curvature peak scalar and can be used to quickly eliminate the lateral acceleration and heading at the end of the lane change. Therefore, different c values can generate different lane‐changing paths for different needs without having to change the start and target configurations. When the value of c is set, the traversal method is the simplest algorithm to find the intermediate point that satisfies (13).Lateral tracking controllerThe ability to manoeuvre while traveling along the planned lane‐changing path is also very important for intelligent vehicles because it affects the lane‐changing execution and the accuracy of collision prediction. Steering systems based on feedforward‐feedback control architectures have been a major focus of research [30]. The control architecture is shown in Figure 10. This control architecture is well suited for the lane‐changing paths determined by this paper because the path curvature and heading have already been calculated. The feedforward steering wheel angle is determined based on the planned path curvature, as follows:14δFFW=(Lh+Kusvh2)iκdwhere Lh is the host vehicle's wheelbase, vh is the velocity of the host vehicle, i is the steering gear ratio, κd is the desired curvature, and Kus is the under‐steer gradient, written as15Kus=mLhacαr−bcαfwhere m is the vehicle mass at the centre of gravity, a is the front axle distance, b is the rear axle distance, cαf is the front axle slip rigidity with elasticities, and cαr is the rear axle slip rigidity with elasticities.10FIGUREBlock diagram of the feedforward‐feedback steering controllerThe feedback control law is designed to eliminate lateral displacement and heading error. The lateral displacement must be strictly tracked and the heading should also be controlled. Reasonable heading changes will make the occupants feel comfortable. Therefore, a ‘two‐closed‐loop’ feedback control law is designed as shown in Figure 11, which includes a ‘lateral displacement loop’ for realising the planned lateral displacement and a ‘heading loop’ for keeping the actual heading as consistent as possible with the planned heading. This approach has the advantage that the control parameters are easy to determine. The control parameters of the inner loop ‘heading loop’ are determined first. Then, the control parameters of the outer loop ‘lateral displacement loop’ are tuned. P is a proportional regulator and PI is a proportional integral regulator. Kga is the lateral acceleration steady‐state gain and is expressed as16Kga=vh2(Lh+Kusvh2)i.11FIGURELateral feedback control scheme of two closed loopsTherefore, the feedback control law adapts to the vehicle's velocity. The lateral displacement error produces an additional heading command from the ‘lateral displacement loop’. The desired heading and the additional heading produces the overall heading command17φoa=kp1(yd−yfb)+φdwhere kp1 is the lateral displacement proportional gain, yd and φd are the desired lateral distance and heading, respectively, andyfb is the feedback lateral displacement.Then, the desired lateral acceleration is generated by the ‘heading loop’:18ayd=kp2(φoa−φfb)+ki2∫(φoa−φfb)dtwhere kp2 is the heading proportional gain, ki2 is the heading integral gain, and φfb is the feedback heading.The feedback control law is given by19δFB=aydKga.Finally, the required steering wheel angle is the sum of the feed‐forward and feedback steering wheel angles:20δ=δFFW+δFB.SIMULATION AND EXPERIMENTAL RESULTSLane‐changing path planning methods were compared through simulations, and experiments confirm that the flexible lane‐changing path planning method proposed in this work can be used for real‐time lane change.SimulationPath planning simulationFirst, the bi‐elementary path planning method and the improved path planning method proposed in this work were compared in a theoretical environment. The start configuration was set to (0, 0, 0, 0), the initial target configuration was set to (220, 4, 0, 0), the first re‐planned target configuration was set to (250, 6, 0, 0), and the second re‐planned target configuration was set to (200, 0, 0, 0). Because the paths planned by the different planning methods are different, the start configuration of each re‐planning cannot be exactly the same. Thus, to make them as similar as possible, the planned paths were dispersed into 600 points, and the start point of the re‐planning was set to the 100th point of the last planned path.The result of lane‐changing path planning by the basic bi‐elementary path is shown in Figure 12. This method can guarantee the continuity of the displacement and the heading, as shown in Figure 12(a) and (b); however, it cannot guarantee the smoothness of the heading, as shown in Figure 12(b), and there a step occurs in the curvature when re‐planning, as shown in Figure 12(c). This curvature step hinders the use of the feedforward‐feedback control method because it causes an instantaneous change of the steering wheel angle and lateral acceleration. Therefore, there are flaws in the re‐planning of the bi‐elementary path. It is only suitable for specific scenario planning. It is not flexible enough to deal with the re‐planning.12FIGUREThe lane‐changing path planning result by the basic bi‐elementary path. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe lane‐changing path planning result by the method proposed in this work without involving the shape characteristic parameter c is shown in Figure 13. The problem that the heading is not smooth and the curvature is stepwise is eliminated, as shown in Figure 13(b) and (c). It can guarantee the continuity of the curvature when re‐planning. Comparing Figures 12(c) and 13(c), the maximum curvature scalar value of the initial planning is different, although the start and end configurations of these two initial planning are exactly the same. Its reason is that an arc is inserted in the elementary path, which reduces the maximum curvature scalar value.13FIGUREThe lane‐changing path planning result by the proposed method without involving the shape characteristic parameter c. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe lane‐changing path planning result by the method proposed in this work with c=1 is shown in Figure 14. The c=1 value means that the curvature maximum scalar value is minimised and the scalar values of the two peak curvatures in each re‐planning are almost equal, as shown in Figure 14(c). Comparing Figures 13(c) and 14(c), the curvature maximum scalar value re‐planned with c=1 is less than the curvature maximum scalar value re‐planned without c=1. Comparing the second re‐planned heading in Figures 13(b) and 14(b), the heading re‐planned without c=1 gets back faster than the heading re‐planned with c=1, which reduces the movement in the opposite direction. This is actually a case where c is greater than 1. Therefore, choosing a different c can generate different lane‐changing paths. In other words, the shape of the path can be changed without changing the start and target configurations.14FIGUREThe lane‐changing path planning result by the proposed method with c=1. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe fifth‐degree polynomial path planning method was also adopted for comparison. In the field of interpolation path planning methods, it is widely used and can also be used to plan a path with heading and curvature information. To ensure easy calculation of the heading and curvature, the expression that lateral displacement is the fifth‐degree polynomial of longitudinal displacement is used [6]. The lane‐changing path planning result by the fifth‐degree polynomial method is shown in Figure 15. The polynomial ensures the continuity of heading and curvature when re‐planning, as shown in Figure 15(b) and (c). Its planned curvature is different from the curvature planned by the method based on clothoid, as shown in Figures 12(c), 13(c), 14(c), and 15(c). Its planned curvature does not change linearly. And when the start and target configurations are fixed, the path planned by the polynomial is also fixed. If the path needs to be changed, an intermediate configuration must be added for segment planning, but the intermediate configuration is difficult to determine clearly.15FIGUREThe lane‐changing path planning result by the fifth‐degree polynomial. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureLane‐changing simulationA lane‐changing simulation was carried out by MATLAB and CARSIM. An E‐class vehicle was selected, and its velocity was set to 70 km/h. The vehicle first changes lane to the left lane and cancels the lane change at 3 s. Then, it returns to the centre of the original lane and changes lane to the left lane again at 11 s. The lane‐changing simulation result of the method proposed in this work is shown in Figure 16. The lane‐changing task was completed well. The lane‐changing simulation result of the fifth‐degree polynomial is shown in Figure 17. The lane‐changing paths are almost the same as those shown in Figures 16(a) and 17(a). The headings are continuous and smooth, as shown in Figures 16(c) and 17(c). However, the steering wheel angle changes roughly linearly in Figure 16(b), which is different from that in Figure 17(b). This result is primarily due to the different curvatures planned by these two methods, compared in Section 4.1.1, and the feedforward control. It also causes that the maximum lateral acceleration scalar value shown in Figure 16(d) is smaller than that shown in Figure 17(d). Both methods can flexibly complete the lane‐changing planning task. The main difference is that the method proposed in this work can plan different curvatures.16FIGUREThe lane‐changing simulation result of the proposed method. (a) Comparison of the lateral displacement. (b) The steering wheel angle. (c) The heading. (d) The lateral acceleration17FIGUREThe lane‐changing simulation result of the fifth‐degree polynomial. (a) Comparison of the lateral displacement. (b) The steering wheel angle. (c) The heading. (d) The lateral accelerationExperimentTwo tests were carried out, based on an experimental platform for autonomous vehicles. These tests were conducted on a four‐lane road, where the width of each lane is 3.4 m. The vehicle speed was controlled near 70 km/h. To make reasonable use of the computing resources, the planning and check task were performed in a 100‐ms time step, while the control task was performed in a 10‐ms time step.The experimental platform for autonomous vehicles is shown in Figure 18. It consists of a car equipped with sensors, including cameras, millimetre‐waves, radars, and differential GPS with an inertial measurement unit. The MPC5675K embedded platform for lane‐changing path planning and control is installed in the trunk, as shown in Figure 18(b).18FIGUREThe experimental platform. (a) The autonomous vehicle. (b) The data acquisition and embedded control systemsThe first test was a left adjacent lane change, in which the task configuration (150, 3.4, 0, 0) was specified and no obstacles were present. It took 45 ms to complete the lane‐changing path planning. The test results are shown in Figure 19. It can be seen from Figure 19(a) that the lane‐changing task was successfully completed. Additionally, the lane‐changing process was comfortable, as shown in Figure 19(b)–(d). The maximum lateral displacement error was less than 15 cm. The maximum lateral acceleration was less than 0.6 m/s2 and the maximum jerk was less than 0.4 m/s3. All these results demonstrate that the path planning and tracking method proposed in this work is suitable for lane change. The lateral displacement error began to increase rapidly, and the heading had a zero‐order hold at approximately 69.4 s, as shown in Figure 19(a), which was probably caused by the steering wheel gap. The steering wheel angle crossed through zero at approximately 69.4 s, as shown in Figure 19(c).19FIGUREThe experimental results of the first test. (a) Comparison of the lateral displacement. (b) The actual heading. (c) The actual steering wheel angle. (d) The actual lateral accelerationThe second test involved returning to the original lane when it was found that the target lane was not available in the process of the lane change. It took 56 ms to re‐plan the lane‐changing path. The test results are shown in Figure 20. The vehicle first changed lanes to the left adjacent lane and began to return to the original lane at 19.5 s, as shown in Figure 20(a). The desired lateral displacement step at 19.5 s in Figure 20(a) was caused by path re‐planning. But it did not result in a step of the actual heading and lateral acceleration, as shown in Figure 20(b) and (d). The path planning method proposed in this work is able to plan the path according to the current state of the vehicle. The actual lateral displacement, the actual heading, and the actual steering wheel angle were nonzero at the beginning of the path planning and re‐planning, as shown in Figure 20(a)–(c), and these values were used as initial input. Therefore, the lateral displacement error and heading error are zero when the lane‐changing path is re‐planned. The proposed method avoids generating step control input, as shown in Figure 20(c).20FIGUREThe experimental results of the second test. (a) Comparison of the lateral distance. (b) The actual heading. (c) The actual steering wheel angle. (d) The actual lateral accelerationThe above two tests prove that the path planning method proposed in this work is feasible. And it is flexible enough to adapt to a dynamic traffic while keeping the lane‐changing path smooth and the curvature continuous.CONCLUSIONSThis paper proposes a method of planning flexible and smooth paths for the lane‐changing manoeuvres of autonomous vehicles. The designed method mainly solves the problem of curvature discontinuity in path re‐planning, and a lateral controller is designed to ensure that the lane‐changing path is followed well. The shape characteristicc is designed. It can generate different lane‐changing paths for different needs without changing the start and target configurations. Clothoid approximation and lookup tables are used to reduce the computational time. Simulations were devised to verify the smooth continuity of the path planned by the proposed method. The shape characteristicc allows the lane‐changing path to generate different features. Furthermore, lane‐changing experiments based on the MPC5675K embedded controller platform were performed to demonstrate the feasibility of the proposed method.However, the proposed path planning method cannot generate a path when the lateral displacement is larger than the longitudinal displacement. In future work, a test with embedded longitudinal MPC control in complex scenarios will be performed. How to apply the proposed path planning method in the lateral control authority transition field for semi‐autonomous driving will be researched.ACKNOWLEDGEMENTSThis work was supported by the National Key R&D Program of China under Grant 2017YFB0103600.REFERENCESHuang, Y., et al.: A novel local motion planning framework for autonomous vehicles based on resistance network and model predictive control. IEEE Trans. Veh. Technol. 69(1), 55–66 (2020)Anderson, S.J., et al.: Constraint‐based planning and control for safe, semi‐autonomous operation of vehicles. In: Proc. IEEE Intelligent Vehicles Symposium, vol. 1, pp. 383–388 (2012)Anderson, S.J., et al.: An optimal‐control‐based framework for trajectory planning, threat assessment, and semi‐autonomous control of passenger vehicles in hazard avoidance scenarios. Int. J. Veh. Auton. Syst. 8, 190–216 (2010)Erlien, S.M., et al.: Shared steering control using safe envelopes for obstacle avoidance and vehicle stability. IEEE Trans. Intell. Transp. Syst. 17(2), 441–451 (2016)Gonzalez, D., et al.: A review of motion planning techniques for automated vehicles. IEEE Trans. Intell. Transp. Syst. 17(4), 1135–1145 (2016)Sledge, N.H., Marshek, K.M.: Comparison of ideal vehicle lane‐change trajectories. SAE Trans. 6(4), 233–256 (1997)Chen, P., et al.: Path planning strategy for vehicle navigation based on user habits. Appl. Sci. 8(3), 407–431 (2018)Zhu, B., et al.: A lane‐changing decision‐making method for intelligent vehicle based on acceleration field. SAE Int. J. Passenger Cars – Electron. Electr. Syst. 11(3), 219–230 (2018)Funke, J., et al.: Collision avoidance and stabilization for autonomous vehicles in emergency scenarios. IEEE Trans. Control Syst. Technol. 25(4), 1204–1216 (2017)Zhao, D., et al.: Accelerated evaluation of automated vehicles safety in lane‐change scenarios based on importance sampling techniques. IEEE Trans. Intell. Transp. Syst. 18(3), 595–607 (2017)Huang, Y., et al.: A motion planning and tracking framework for autonomous vehicles based on artificial potential field elaborated resistance network approach. IEEE Trans. Ind. Electron. 67(2), 1376–1386 (2020)Wang, C., et al.: Lane change warning threshold based on driver perception characteristics. Accid. Anal. Prev. 117, 164–174 (2018)Moon, C., et al.: Investigation of objective parameters for acceptance evaluation of automatic lane change system. Int. J. Automot. Technol. 19(1), 179–190 (2017)Geng, G., et al.: Study on path planning method for imitating the lane‐changing operation of excellent drivers. Appl. Sci. 8(5), 814–833 (2018)Beggiato, M., et al.: Lane change prediction: From driver characteristics, manoeuvre types and glance behaviour to a real‐time prediction algorithm. In: UR:BAN Human Factors in Traffic, pp. 205–221.Springer, New York (2018)Reeds, J.: Optimal paths for a car that goes both forwards and backwards. Pacific J. Math 145(2), 367–393 (1990)Heil, T., et al.: Adaptive and efficient lane change path planning for automated vehicles. In: IEEE International Conference on Intelligent Transportation Systems, pp. 479–484, (2016)Papadimitriou, I., Tomizuka, M.: Fast lane changing computations using polynomials. In: Proc. American Control Conference, pp. 48–53, (2003)Bae, I., et al.: Path generation and tracking based on a Bézier curve for a steering rate controller of autonomous vehicles. In: Proc. 16th International IEEE Conference on Intelligent Transportation Systems, pp. 436–441, (2013)Shiller, Z., Gwo, Y.R.: Dynamic motion planning of autonomous vehicles. IEEE Trans. Rob. Autom. 7(2), 241–249 (1991)Berglund, T., et al.: Planning smooth and obstacle‐avoiding b‐spline paths for autonomous mining vehicles. IEEE Trans. Autom. Sci. Eng. 7(1), 167–172 (2010)Khosla, D.: Accurate estimation of forward path geometry using two‐clothoid road model. In: Proc. IEEE Intell. Veh. Symp., vol. 1, pp. 154–159 (2003)AASHTO: A Policy on Geometric Design of Highways and Streets, 6th ed., American Association of State Highway and Transportation Officials, Washington (2011)Abramowitz, M., Stegun, I.A., (eds.): Handbook of Mathematical Functions with Formulas, Graphs, and Mathematical Tables. National Institute of Standards and Technology, Gaithersburg (1972)Scheuer, A., Fraichard, T.: Planning continuous‐curvature paths for car‐like robots. In Proc. IEEE/RSJ Int. Conf. Intell. Robots Syst., pp. 1304–1311, (1996)Funke, J., Christian Gerdes, J.: Simple clothoid lane change trajectories for automated vehicles incorporating friction constraints. J. Dyn. Syst. Meas. Control 138(2), 1–9 (2016)Kanayama, Y.J., Hartman, B.I.: Smooth local‐path planning for autonomous vehicles. In: Autonomous Robot Vehicles, pp. 62–67.Springer, New York (1990)Brezak, M., Petrovic, I.: Real‐time approximation of clothoids with bounded error for path planning applications. IEEE Trans. Rob. 30(2), 507–515 (2014)Sánchez‐Reyes, J., Chacón, J.M.: Polynomial approximation to clothoids via s‐power series. Comput.‐Aided Des. 35(14), 1305–1313 (2003)Kapania, N.R., Gerdes, J.C.: Design of a feedback‐feedforward steering controller for accurate path tracking and stability at the limits of handling. Veh. Syst. Dyn. 53(12), 1687–1704 (2015) http://www.deepdyve.com/assets/images/DeepDyve-Logo-lg.png IET Intelligent Transport Systems Wiley

Planning flexible and smooth paths for lane‐changing manoeuvres of autonomous vehicles

Loading next page...
 
/lp/wiley/planning-flexible-and-smooth-paths-for-lane-changing-manoeuvres-of-1JrBXfJ5Pw

References (32)

Publisher
Wiley
Copyright
© 2021 The Institution of Engineering and Technology
eISSN
1751-9578
DOI
10.1049/itr2.12014
Publisher site
See Article on Publisher Site

Abstract

INTRODUCTIONAutonomous vehicle technology has received much attention recently. Autonomous vehicles can improve traffic safety, occupant comfort, and convenience in daily life. Advanced driver assistance systems, such as lane‐keeping assistance, adaptive cruise control (ACC), and automatic emergency braking, are already available in production vehicles. Technologies for lane‐changing manoeuvres of autonomous vehicles have also proven very useful and have been widely studied. The lane‐changing manoeuvres can be considered a component that involves both longitudinal and lateral control [1]. The longitudinal control ensures that the vehicle maintains a safe distance from surrounding vehicles. This aspect can be fulfilled by an ACC. The lateral control causes the vehicle to move laterally to the target lane. Some lateral control methods based on model‐predictive control do not require a planned path [2, 4], but most lateral control methods require a target path for tracking. An appropriate lane‐changing path can also function as a good reference input for model‐predictive control. Therefore, a lane‐changing path or a lane‐changing path planning method is a very important part of the lane change.Motion planning techniques and ideal vehicle lane‐changing trajectories have been summarised and compared in the literature [5, 6]. Motion planning techniques are divided into global and local planning and can be classified into four groups: graph search, sampling, interpolating, and numerical optimisation. Interpolating and graph search are the two main algorithms applied in real‐world implementations. Lane‐changing path planning problems are an aspect of local planning and can be solved by interpolation. The desired vehicle trajectories in lane changes are evaluated from the length, curvature, curvature derivatives, and critical speed [6]. And the lane‐changing paths should also be personalised [7, 8], safety, collision avoidance, and stabilisation [9–11]. The acceptance of the driver has also to be considered [12–14]. Therefore, it is very important to predict the entire lane‐changing path [15]. It can evaluate the information above before performing the lane change.The line and circle curve planner [16] was first considered because of its low computational cost. However, it cannot be accepted because a sudden trajectory change from a line to a circle will induce an instantaneous change in the lateral acceleration, causing an infinite jerk. The polynomial curve planner is also a good choice with low computational cost [17, 18]. However, as the design parameters of the path increase, the degree of the polynomial increases, making it increasingly difficult to solve the coefficients. Moreover, if the start and target configurations are fixed, it is difficult to adjust the middle section of the polynomial path. Bezier curves and B‐splines are suitable for obtaining smooth paths [19–21], but it is not easy to calculate the curvature and heading of the path when the maximum limits of the lateral acceleration and jerk are considered.Clothoids are a natural choice for lane‐changing path planning because they have already been applied in road design [22, 23] and have the advantage of linearly changing curvature. Thus, a path planned by clothoids is easy to follow and results in higher tracking accuracy. Unfortunately, clothoids are defined in terms of Fresnel integrals [24], making clothoid‐form path solutions difficult to be achieved analytically. Scheuer and Fraichard created a subset of clothoid‐based paths called bi‐elementary paths, for which closed‐form expressions exist to obtain solutions [25]. Funke and Christian Gerdes applied bi‐elementary paths to design lane‐changing trajectories for automated vehicles and achieved good results [26]. However, it is not flexible and only suitable for planning initial lane‐changing path from straight to straight. In other words, the planned path should be zero heading and curvature at the start and end, which is not suitable for real‐time changing traffic environment.To solve these problems, this paper proposes a new lane‐changing path planning algorithm. Clothoid and arc curves are superimposed on the bi‐elementary path based on longitudinal distance, making the path planning method sufficiently flexible to adapt to real‐time changing traffic environment. The proposed method also maintains a continuous curvature and heading under path planning or re‐planning and is no longer restricted to zero heading and curvature at the start and end. When the start and target configurations are fixed, different shapes of the lane‐changing path can be generated for different personal habits. A lookup table method is applied, and an appropriate accuracy is used for the clothoid expression, allowing the algorithm to run on the embedded hardware platforms of production vehicles. Finally, a tracking controller suitable for the path planning method proposed in this work is designed for a better tracking accuracy.The remainder of this paper is organised as follows. In Section 2, the framework of a lateral lane‐changing control system and the main parameters are introduced. Lane‐changing path planning and tracking methods are introduced in Section 3. In Section 4, simulation comparison and experimental results are reported to demonstrate the feasibility of the proposed lane‐changing path planning method. Finally, the conclusions of this paper are summarised in Section 5.FRAMEWORK DESCRIPTIONThis section introduces the framework of the lateral lane‐changing control system used in this paper. The framework is depicted in Figure 1. The longitudinal control is not included because this paper studies lateral lane‐changing path planning based on decoupled lane change. The longitudinal control aspect can be served by an ACC to maintain a safe distance with surrounding vehicles. The changes in longitudinal speed under the limits will not affect the framework. The limits are given by the maximum curvature of the planned lane‐changing path [26], and the lateral tracking controller designed is adaptive speed. The framework leverages path planning and lateral tracking to perform a lateral lane‐changing task. First, a lane‐changing intention is generated based on vehicle status and environmental information. Second, the start configuration is generated based on the vehicle status and target configuration is generated based on the target lane and comfort or obstacles restriction. Then, a lane‐changing path is generated by the method proposed in this work based on the configurations, after which the generated path is checked. If the path is not collision‐free, the configurations and lane‐changing path are regenerated. Finally, the lateral tracking controller generates a steering wheel angle command for the electric power steering system (EPS) with an angle interface based on the lane‐changing path and vehicle velocity.1FIGUREThe diagram of the lateral lane‐changing control systemThe main parameters for the generation of a lane‐changing path and the lateral tracking controller are shown in Table 1.1TABLEThe main parameters for generating a lane‐changing path and the lateral tracking controllerSymbolDescriptionUnitsxLongitudinal distancemyLateral displacementmφHeadingradκCurvature1/mσSharpness1/m2λArc length fraction1DFraction for solving the length of an elementary path1LsLength of a clothoid curvemvhVehicle velocitym/sKusUnder‐steer gradients2/mLhVehicle wheelbasemKgaLateral acceleration steady‐state gainm/s2kp1Lateral displacement proportional gain1kp2Heading proportional gain1ki2Heading integral gain1LANE‐CHANGING PATH PLANNING AND TRACKINGThe bi‐elementary path for lane‐changing planning and its real‐time calculationA bi‐elementary path is composed of two elementary paths. An elementary path Π(l,κ) is constructed by two segments of clothiods, as shown in Figure 2. The first clothoid is named as ‘entry clothoid’ and the second clothoid is named as ‘exit clothoid’ [26]. The total length of the elementary path Π(l,κ) is described by l, and the path curvature profile k is a linear function of its arc length s, i.e., k(s)=σs, where σ is a real constant called the sharpness of the clothoid. Therefore, the path Π(l,κ) can be expressed as1k(s)=σs∀s∈[0,ll22]k(s)=σ(l−s)∀s∈[ll22,l].2FIGUREAn elementary path composed of two clothoidsThe curvature profile with a strictly positive σ is shown in Figure 3. Its curvature increases linearly from zero to a maximum of k(l/l22)=σl/σl22 and then decreases linearly back to zero. Obviously, this elementary path curvature is symmetric and the path is symmetric. The start and end configurations of the elementary path are q0(x0,y0,φ0) and ql(xl,yl,φl), respectively. Consequently, the change of heading Δψ from the start configuration to the end configuration can be expressed as2Δψ=φl−φ0=2θ=2tan−1yl−y0xl−x0.3FIGUREThe curvature profile of the elementary pathTo reduce the maximum curvature, an arc is inserted into the elementary paths, as shown in Figure 4. However, this increases the computational complexity of an elementary path length, which is expressed as [26]3l=dDΔψ,λwhere dis the distance between the start and end points of an elementary path and D(Δψ,λ)is a parameter from the geometry of a symmetric path given Δψ and λ. D(Δψ,λ) is expressed as4DΔψ,λ=2∫00.5cosfzdzwhere f(z) is given by5fz=2Δψ1+λz∀z∈0,λ22Δψ1−λ2−z2+z−λ24∀z∈λ2,12and λ∈[0,1] is the inserted arc length fraction.4FIGUREAn elementary path with an arcTo simplify the calculation of the parameter D(Δψ,λ) for embedded platforms, a lookup table method is designed. Because the change of heading Δψ is small and bounded during the lane change, and the parameter D(Δψ,λ) monotonically decreases with |Δψ| and increases with λ, a lookup table method is feasible. The table is shown as Figure 5. The parameter D(Δψ,λ) is calculated online by lookup table through the input of |Δψ| and λ.5FIGUREThe lookup table of the parameter D(Δψ,λ)Two elementary paths comprise a bi‐elementary path, as shown in Figure 6. The start configuration is qs(xs,ys,φs) and the target configuration is qt(xt,yt,φt). An intermediate configuration qi(xi,yi,φi) is needed to connect qs(xs,ys,φs) and qt(xt,yt,φt) with two elementary paths. The candidate intermediate configurations are given in [27].6FIGURETwo bi‐elementary paths of parallel and non‐parallel configurationsIf the orientations of qsand qtare parallel, the intermediate configurations qi1(xi1,yi1,φi1) are located on a line passing through qs and qt, as shown in Figure 6, which can be expressed as6(xi1−xs)(yi1−yt)=(xi1−xt)(yi1−ys).In contrast, when the orientations of qsand qtare not parallel, the intermediate configurations qi2(xi2,yi2,φi2) are located on a circle passing through qs and qt, as shown in Figure 6, which can be expressed as7(xi2−xs)(yi2−yt)−(xi2−xt)(yi2−ys)=(xi2−xs)(xi2−xt)+(yi2−ys)(yi2−yt)tan(φt−φs2).Clothoids are the basis of a bi‐elementary path. Therefore, the simpler the coordinate calculation of clothoids is, the more efficient the real‐time calculation is. A real‐time approximation of clothoids with a bounded error for a path planning application method was proposed in [28]. This method is based on lookup tables and improves the approximation of clothoids under large lengths. It requires storing large basic clothoids and using circular interpolation. For clothoids under small lengths, applying the two‐point analogue of Taylor expansions [29] to compute the clothoid coordinates is easier. The basic clothoids, which are the heading and the curvature, start with zero and are expressed as8xls=ls−ls540Rs2Ls2yls=ls36RsLs−ls7336Rs3Ls3φls=ls22RsLswhere ls is the length between the start point and any point in the clothoid, Ls is the total length of the clothoid, Rs is the radius at the end point of the clothoid, x(ls) and y(ls) are the coordinates of the clothoid in the Cartesian coordinate system, and φ(ls) is the heading in the Cartesian coordinate system.The clothoid curves whose initial orientations are non‐zero can be obtained by coordinate transformation from the basic clothoids:9XY=cosφs−sinφssinφscosφsxy.A flexible lane‐changing path planning methodNormally, a lane‐changing manoeuvre transitions a vehicle from one straight lane into another. In this circumstance, the vehicle's heading at the start and end of a lane change should be equal to zero. Furthermore, the curvatures at the start and end of a lane change are also zero. Bi‐elementary paths can satisfy these conditions, and for a straight lane, there is no problem with directly applying bi‐elementary paths for generating the initial lane‐changing paths. However, lane changes may also occur on a curved lane when the field of view is good and the lane curvature is small. Additionally, the lane‐changing paths also need to be re‐planned when the traffic environment changes. In both the above two cases, the curvatures at the start and end of the lane‐changing paths are non‐zero. Unfortunately, bi‐elementary paths are not flexible enough to adapt to these situations, and they also are unable to keep the curvature continuous when re‐planning.To avoid the restriction imposed by the requirement of the initial and end zero curvature condition, curvature information is introduced into the planning. The configuration is redefined as q(x,y,φ,κ), and extra curve paths are superimposed on the bi‐elementary path based on the longitudinal distance to make the curvature controllable. Based on different start curvature κs and target curvature κt conditions, it can be divided into three cases to superimpose the curve paths on the bi‐elementary path, as shown in Table 2.2TABLEConditions for superimposing curvesCaseConditionSuperimposed curve path1κs≠0,κt=0 or κs≠0,κt=0Clothoid2κs=κt,κs≠0,κt≠0Arc3κs≠κt,κs≠0,κt≠0Arc and clothoidFor all cases, the general planning process is described in Figure 7. Start and target configurations of the superimposed curve path s1 and the bi‐elementary path s2 are solved first, and then superimposed curve path s1 and bi‐elementary path s2 are planned. Paths s1 and s2 are superimposed together based on the longitudinal distance to obtain the final lane‐changing path.7FIGUREThe general planning process for all casesThe problem of the process is how to calculate the new configurations. For the first case, taking conditions κs≠0andκt=0 as example, φt1 is set to be zero in order to simplify the calculation; therefore, φt2 is equal to φt. yt1 and φs1 can be calculated by (8) and (9), because path s1 is a basic clothoid rotated 180°. φs2 is calculated by φs2=φs−φs1, and yt2 is calculated by yt2=yt−yt1. The planned lane‐changing path s, superimposed clothoid path s1 and bi‐elementary path s2 are shown in Figure 8. For the second case, φs1 is set to be zero in order to simplify the calculation, therefore φs2 is equal to φs. Because the arc path s1 is a circle curve and its constant curvature is set to be κs, yt1 can be calculated as10yt1=ys−signks1κs2−xt−xs2+1κs.8FIGURELane‐changing path planning of the first caseAnd φt1 can be calculated as11φt1=2arctanyt1xt−xs.Then, φt2 is calculated by φt2=φt−φt1, and yt2 is calculated by yt2=yt−yt1. The planned lane‐changing path s, superimposed arc path s1, and bi‐elementary path s2 are shown in Figure 9.9FIGURELane‐changing path planning of the second caseFor the third case, the configurations of the arc path are solved first as in the second case, and the only difference is that its constant curvature is set to be κt. The target lateral coordinate ytc and heading φtc of the arc path are calculated by (10) and (11). Therefore, the other configurations can be expressed as qso(xs,ys,φs,κs−κt) and qto(xt,yt−ytc,φt−φtc,0), and this is the same as the first case.The above method can keep the curvature continuous when re‐planning, and it adapts to non‐zero curvatures at the start and end. To minimise the maximum scalar value of the curvature of the lane‐changing path, the appropriate intermediate configuration must be determined. A bi‐elementary path has both a positive curvature peak and a negative curvature peak. Each curvature peak is the curvature peak of the elementary path, as shown in Figure 3. When the intermediate point moves in the candidate intermediate curve, one curvature peak scalar will increase and the other curvature peak scalar will decrease. There is an intermediate point that makes the two curvature peak scalars equal and minimum. The curvature peak scalar can be expressed as12κsmax=l2σ=4Dθdwhere σ is given byσ=4Δψl2 [26]. To characterise the relationship between the two curvature peak scalars, the parameter c is defined as13c=κs1maxκs2maxwhere κs1maxis the first curvature peak scalar and κs2max is the second curvature peak scalar. Here, c not only represents the relationship between the two curvature peak scalars, but also determines the shape of the planned path. Therefore, c is a shape characteristic parameter of the planned lane‐changing path. When c equals 1, the two curvature peak scalars are equal and minimal, which is the target in this paper. When c is greater than 1, the first curvature peak scalar is greater than the second curvature peak scalar and can be used to quickly generate the lateral acceleration and heading at the beginning of the lane change. When c is less than 1, the first curvature peak scalar is less than the second curvature peak scalar and can be used to quickly eliminate the lateral acceleration and heading at the end of the lane change. Therefore, different c values can generate different lane‐changing paths for different needs without having to change the start and target configurations. When the value of c is set, the traversal method is the simplest algorithm to find the intermediate point that satisfies (13).Lateral tracking controllerThe ability to manoeuvre while traveling along the planned lane‐changing path is also very important for intelligent vehicles because it affects the lane‐changing execution and the accuracy of collision prediction. Steering systems based on feedforward‐feedback control architectures have been a major focus of research [30]. The control architecture is shown in Figure 10. This control architecture is well suited for the lane‐changing paths determined by this paper because the path curvature and heading have already been calculated. The feedforward steering wheel angle is determined based on the planned path curvature, as follows:14δFFW=(Lh+Kusvh2)iκdwhere Lh is the host vehicle's wheelbase, vh is the velocity of the host vehicle, i is the steering gear ratio, κd is the desired curvature, and Kus is the under‐steer gradient, written as15Kus=mLhacαr−bcαfwhere m is the vehicle mass at the centre of gravity, a is the front axle distance, b is the rear axle distance, cαf is the front axle slip rigidity with elasticities, and cαr is the rear axle slip rigidity with elasticities.10FIGUREBlock diagram of the feedforward‐feedback steering controllerThe feedback control law is designed to eliminate lateral displacement and heading error. The lateral displacement must be strictly tracked and the heading should also be controlled. Reasonable heading changes will make the occupants feel comfortable. Therefore, a ‘two‐closed‐loop’ feedback control law is designed as shown in Figure 11, which includes a ‘lateral displacement loop’ for realising the planned lateral displacement and a ‘heading loop’ for keeping the actual heading as consistent as possible with the planned heading. This approach has the advantage that the control parameters are easy to determine. The control parameters of the inner loop ‘heading loop’ are determined first. Then, the control parameters of the outer loop ‘lateral displacement loop’ are tuned. P is a proportional regulator and PI is a proportional integral regulator. Kga is the lateral acceleration steady‐state gain and is expressed as16Kga=vh2(Lh+Kusvh2)i.11FIGURELateral feedback control scheme of two closed loopsTherefore, the feedback control law adapts to the vehicle's velocity. The lateral displacement error produces an additional heading command from the ‘lateral displacement loop’. The desired heading and the additional heading produces the overall heading command17φoa=kp1(yd−yfb)+φdwhere kp1 is the lateral displacement proportional gain, yd and φd are the desired lateral distance and heading, respectively, andyfb is the feedback lateral displacement.Then, the desired lateral acceleration is generated by the ‘heading loop’:18ayd=kp2(φoa−φfb)+ki2∫(φoa−φfb)dtwhere kp2 is the heading proportional gain, ki2 is the heading integral gain, and φfb is the feedback heading.The feedback control law is given by19δFB=aydKga.Finally, the required steering wheel angle is the sum of the feed‐forward and feedback steering wheel angles:20δ=δFFW+δFB.SIMULATION AND EXPERIMENTAL RESULTSLane‐changing path planning methods were compared through simulations, and experiments confirm that the flexible lane‐changing path planning method proposed in this work can be used for real‐time lane change.SimulationPath planning simulationFirst, the bi‐elementary path planning method and the improved path planning method proposed in this work were compared in a theoretical environment. The start configuration was set to (0, 0, 0, 0), the initial target configuration was set to (220, 4, 0, 0), the first re‐planned target configuration was set to (250, 6, 0, 0), and the second re‐planned target configuration was set to (200, 0, 0, 0). Because the paths planned by the different planning methods are different, the start configuration of each re‐planning cannot be exactly the same. Thus, to make them as similar as possible, the planned paths were dispersed into 600 points, and the start point of the re‐planning was set to the 100th point of the last planned path.The result of lane‐changing path planning by the basic bi‐elementary path is shown in Figure 12. This method can guarantee the continuity of the displacement and the heading, as shown in Figure 12(a) and (b); however, it cannot guarantee the smoothness of the heading, as shown in Figure 12(b), and there a step occurs in the curvature when re‐planning, as shown in Figure 12(c). This curvature step hinders the use of the feedforward‐feedback control method because it causes an instantaneous change of the steering wheel angle and lateral acceleration. Therefore, there are flaws in the re‐planning of the bi‐elementary path. It is only suitable for specific scenario planning. It is not flexible enough to deal with the re‐planning.12FIGUREThe lane‐changing path planning result by the basic bi‐elementary path. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe lane‐changing path planning result by the method proposed in this work without involving the shape characteristic parameter c is shown in Figure 13. The problem that the heading is not smooth and the curvature is stepwise is eliminated, as shown in Figure 13(b) and (c). It can guarantee the continuity of the curvature when re‐planning. Comparing Figures 12(c) and 13(c), the maximum curvature scalar value of the initial planning is different, although the start and end configurations of these two initial planning are exactly the same. Its reason is that an arc is inserted in the elementary path, which reduces the maximum curvature scalar value.13FIGUREThe lane‐changing path planning result by the proposed method without involving the shape characteristic parameter c. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe lane‐changing path planning result by the method proposed in this work with c=1 is shown in Figure 14. The c=1 value means that the curvature maximum scalar value is minimised and the scalar values of the two peak curvatures in each re‐planning are almost equal, as shown in Figure 14(c). Comparing Figures 13(c) and 14(c), the curvature maximum scalar value re‐planned with c=1 is less than the curvature maximum scalar value re‐planned without c=1. Comparing the second re‐planned heading in Figures 13(b) and 14(b), the heading re‐planned without c=1 gets back faster than the heading re‐planned with c=1, which reduces the movement in the opposite direction. This is actually a case where c is greater than 1. Therefore, choosing a different c can generate different lane‐changing paths. In other words, the shape of the path can be changed without changing the start and target configurations.14FIGUREThe lane‐changing path planning result by the proposed method with c=1. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureThe fifth‐degree polynomial path planning method was also adopted for comparison. In the field of interpolation path planning methods, it is widely used and can also be used to plan a path with heading and curvature information. To ensure easy calculation of the heading and curvature, the expression that lateral displacement is the fifth‐degree polynomial of longitudinal displacement is used [6]. The lane‐changing path planning result by the fifth‐degree polynomial method is shown in Figure 15. The polynomial ensures the continuity of heading and curvature when re‐planning, as shown in Figure 15(b) and (c). Its planned curvature is different from the curvature planned by the method based on clothoid, as shown in Figures 12(c), 13(c), 14(c), and 15(c). Its planned curvature does not change linearly. And when the start and target configurations are fixed, the path planned by the polynomial is also fixed. If the path needs to be changed, an intermediate configuration must be added for segment planning, but the intermediate configuration is difficult to determine clearly.15FIGUREThe lane‐changing path planning result by the fifth‐degree polynomial. (a) The planned lane‐changing paths. (b) The planned lane‐changing heading. (c) The planned lane‐changing curvatureLane‐changing simulationA lane‐changing simulation was carried out by MATLAB and CARSIM. An E‐class vehicle was selected, and its velocity was set to 70 km/h. The vehicle first changes lane to the left lane and cancels the lane change at 3 s. Then, it returns to the centre of the original lane and changes lane to the left lane again at 11 s. The lane‐changing simulation result of the method proposed in this work is shown in Figure 16. The lane‐changing task was completed well. The lane‐changing simulation result of the fifth‐degree polynomial is shown in Figure 17. The lane‐changing paths are almost the same as those shown in Figures 16(a) and 17(a). The headings are continuous and smooth, as shown in Figures 16(c) and 17(c). However, the steering wheel angle changes roughly linearly in Figure 16(b), which is different from that in Figure 17(b). This result is primarily due to the different curvatures planned by these two methods, compared in Section 4.1.1, and the feedforward control. It also causes that the maximum lateral acceleration scalar value shown in Figure 16(d) is smaller than that shown in Figure 17(d). Both methods can flexibly complete the lane‐changing planning task. The main difference is that the method proposed in this work can plan different curvatures.16FIGUREThe lane‐changing simulation result of the proposed method. (a) Comparison of the lateral displacement. (b) The steering wheel angle. (c) The heading. (d) The lateral acceleration17FIGUREThe lane‐changing simulation result of the fifth‐degree polynomial. (a) Comparison of the lateral displacement. (b) The steering wheel angle. (c) The heading. (d) The lateral accelerationExperimentTwo tests were carried out, based on an experimental platform for autonomous vehicles. These tests were conducted on a four‐lane road, where the width of each lane is 3.4 m. The vehicle speed was controlled near 70 km/h. To make reasonable use of the computing resources, the planning and check task were performed in a 100‐ms time step, while the control task was performed in a 10‐ms time step.The experimental platform for autonomous vehicles is shown in Figure 18. It consists of a car equipped with sensors, including cameras, millimetre‐waves, radars, and differential GPS with an inertial measurement unit. The MPC5675K embedded platform for lane‐changing path planning and control is installed in the trunk, as shown in Figure 18(b).18FIGUREThe experimental platform. (a) The autonomous vehicle. (b) The data acquisition and embedded control systemsThe first test was a left adjacent lane change, in which the task configuration (150, 3.4, 0, 0) was specified and no obstacles were present. It took 45 ms to complete the lane‐changing path planning. The test results are shown in Figure 19. It can be seen from Figure 19(a) that the lane‐changing task was successfully completed. Additionally, the lane‐changing process was comfortable, as shown in Figure 19(b)–(d). The maximum lateral displacement error was less than 15 cm. The maximum lateral acceleration was less than 0.6 m/s2 and the maximum jerk was less than 0.4 m/s3. All these results demonstrate that the path planning and tracking method proposed in this work is suitable for lane change. The lateral displacement error began to increase rapidly, and the heading had a zero‐order hold at approximately 69.4 s, as shown in Figure 19(a), which was probably caused by the steering wheel gap. The steering wheel angle crossed through zero at approximately 69.4 s, as shown in Figure 19(c).19FIGUREThe experimental results of the first test. (a) Comparison of the lateral displacement. (b) The actual heading. (c) The actual steering wheel angle. (d) The actual lateral accelerationThe second test involved returning to the original lane when it was found that the target lane was not available in the process of the lane change. It took 56 ms to re‐plan the lane‐changing path. The test results are shown in Figure 20. The vehicle first changed lanes to the left adjacent lane and began to return to the original lane at 19.5 s, as shown in Figure 20(a). The desired lateral displacement step at 19.5 s in Figure 20(a) was caused by path re‐planning. But it did not result in a step of the actual heading and lateral acceleration, as shown in Figure 20(b) and (d). The path planning method proposed in this work is able to plan the path according to the current state of the vehicle. The actual lateral displacement, the actual heading, and the actual steering wheel angle were nonzero at the beginning of the path planning and re‐planning, as shown in Figure 20(a)–(c), and these values were used as initial input. Therefore, the lateral displacement error and heading error are zero when the lane‐changing path is re‐planned. The proposed method avoids generating step control input, as shown in Figure 20(c).20FIGUREThe experimental results of the second test. (a) Comparison of the lateral distance. (b) The actual heading. (c) The actual steering wheel angle. (d) The actual lateral accelerationThe above two tests prove that the path planning method proposed in this work is feasible. And it is flexible enough to adapt to a dynamic traffic while keeping the lane‐changing path smooth and the curvature continuous.CONCLUSIONSThis paper proposes a method of planning flexible and smooth paths for the lane‐changing manoeuvres of autonomous vehicles. The designed method mainly solves the problem of curvature discontinuity in path re‐planning, and a lateral controller is designed to ensure that the lane‐changing path is followed well. The shape characteristicc is designed. It can generate different lane‐changing paths for different needs without changing the start and target configurations. Clothoid approximation and lookup tables are used to reduce the computational time. Simulations were devised to verify the smooth continuity of the path planned by the proposed method. The shape characteristicc allows the lane‐changing path to generate different features. Furthermore, lane‐changing experiments based on the MPC5675K embedded controller platform were performed to demonstrate the feasibility of the proposed method.However, the proposed path planning method cannot generate a path when the lateral displacement is larger than the longitudinal displacement. In future work, a test with embedded longitudinal MPC control in complex scenarios will be performed. How to apply the proposed path planning method in the lateral control authority transition field for semi‐autonomous driving will be researched.ACKNOWLEDGEMENTSThis work was supported by the National Key R&D Program of China under Grant 2017YFB0103600.REFERENCESHuang, Y., et al.: A novel local motion planning framework for autonomous vehicles based on resistance network and model predictive control. IEEE Trans. Veh. Technol. 69(1), 55–66 (2020)Anderson, S.J., et al.: Constraint‐based planning and control for safe, semi‐autonomous operation of vehicles. In: Proc. IEEE Intelligent Vehicles Symposium, vol. 1, pp. 383–388 (2012)Anderson, S.J., et al.: An optimal‐control‐based framework for trajectory planning, threat assessment, and semi‐autonomous control of passenger vehicles in hazard avoidance scenarios. Int. J. Veh. Auton. Syst. 8, 190–216 (2010)Erlien, S.M., et al.: Shared steering control using safe envelopes for obstacle avoidance and vehicle stability. IEEE Trans. Intell. Transp. Syst. 17(2), 441–451 (2016)Gonzalez, D., et al.: A review of motion planning techniques for automated vehicles. IEEE Trans. Intell. Transp. Syst. 17(4), 1135–1145 (2016)Sledge, N.H., Marshek, K.M.: Comparison of ideal vehicle lane‐change trajectories. SAE Trans. 6(4), 233–256 (1997)Chen, P., et al.: Path planning strategy for vehicle navigation based on user habits. Appl. Sci. 8(3), 407–431 (2018)Zhu, B., et al.: A lane‐changing decision‐making method for intelligent vehicle based on acceleration field. SAE Int. J. Passenger Cars – Electron. Electr. Syst. 11(3), 219–230 (2018)Funke, J., et al.: Collision avoidance and stabilization for autonomous vehicles in emergency scenarios. IEEE Trans. Control Syst. Technol. 25(4), 1204–1216 (2017)Zhao, D., et al.: Accelerated evaluation of automated vehicles safety in lane‐change scenarios based on importance sampling techniques. IEEE Trans. Intell. Transp. Syst. 18(3), 595–607 (2017)Huang, Y., et al.: A motion planning and tracking framework for autonomous vehicles based on artificial potential field elaborated resistance network approach. IEEE Trans. Ind. Electron. 67(2), 1376–1386 (2020)Wang, C., et al.: Lane change warning threshold based on driver perception characteristics. Accid. Anal. Prev. 117, 164–174 (2018)Moon, C., et al.: Investigation of objective parameters for acceptance evaluation of automatic lane change system. Int. J. Automot. Technol. 19(1), 179–190 (2017)Geng, G., et al.: Study on path planning method for imitating the lane‐changing operation of excellent drivers. Appl. Sci. 8(5), 814–833 (2018)Beggiato, M., et al.: Lane change prediction: From driver characteristics, manoeuvre types and glance behaviour to a real‐time prediction algorithm. In: UR:BAN Human Factors in Traffic, pp. 205–221.Springer, New York (2018)Reeds, J.: Optimal paths for a car that goes both forwards and backwards. Pacific J. Math 145(2), 367–393 (1990)Heil, T., et al.: Adaptive and efficient lane change path planning for automated vehicles. In: IEEE International Conference on Intelligent Transportation Systems, pp. 479–484, (2016)Papadimitriou, I., Tomizuka, M.: Fast lane changing computations using polynomials. In: Proc. American Control Conference, pp. 48–53, (2003)Bae, I., et al.: Path generation and tracking based on a Bézier curve for a steering rate controller of autonomous vehicles. In: Proc. 16th International IEEE Conference on Intelligent Transportation Systems, pp. 436–441, (2013)Shiller, Z., Gwo, Y.R.: Dynamic motion planning of autonomous vehicles. IEEE Trans. Rob. Autom. 7(2), 241–249 (1991)Berglund, T., et al.: Planning smooth and obstacle‐avoiding b‐spline paths for autonomous mining vehicles. IEEE Trans. Autom. Sci. Eng. 7(1), 167–172 (2010)Khosla, D.: Accurate estimation of forward path geometry using two‐clothoid road model. In: Proc. IEEE Intell. Veh. Symp., vol. 1, pp. 154–159 (2003)AASHTO: A Policy on Geometric Design of Highways and Streets, 6th ed., American Association of State Highway and Transportation Officials, Washington (2011)Abramowitz, M., Stegun, I.A., (eds.): Handbook of Mathematical Functions with Formulas, Graphs, and Mathematical Tables. National Institute of Standards and Technology, Gaithersburg (1972)Scheuer, A., Fraichard, T.: Planning continuous‐curvature paths for car‐like robots. In Proc. IEEE/RSJ Int. Conf. Intell. Robots Syst., pp. 1304–1311, (1996)Funke, J., Christian Gerdes, J.: Simple clothoid lane change trajectories for automated vehicles incorporating friction constraints. J. Dyn. Syst. Meas. Control 138(2), 1–9 (2016)Kanayama, Y.J., Hartman, B.I.: Smooth local‐path planning for autonomous vehicles. In: Autonomous Robot Vehicles, pp. 62–67.Springer, New York (1990)Brezak, M., Petrovic, I.: Real‐time approximation of clothoids with bounded error for path planning applications. IEEE Trans. Rob. 30(2), 507–515 (2014)Sánchez‐Reyes, J., Chacón, J.M.: Polynomial approximation to clothoids via s‐power series. Comput.‐Aided Des. 35(14), 1305–1313 (2003)Kapania, N.R., Gerdes, J.C.: Design of a feedback‐feedforward steering controller for accurate path tracking and stability at the limits of handling. Veh. Syst. Dyn. 53(12), 1687–1704 (2015)

Journal

IET Intelligent Transport SystemsWiley

Published: Feb 1, 2021

Keywords: Spatial variables control; Velocity, acceleration and rotation control; Road‐traffic system control; Mobile robots; Traffic engineering computing; Vehicle mechanics

There are no references for this article.