0
Research Papers

Implementation of Reversing Control on a Doubly Articulated Vehicle OPEN ACCESS

[+] Author and Article Information
Amy J. Rimmer

Department of Engineering,
University of Cambridge,
Cambridge CB2 1TN, UK
e-mail: amyrimmer@gmail.com

David Cebon

Department of Engineering,
University of Cambridge,
Cambridge CB2 1TN, UK
e-mail: dc@eng.cam.ac.uk

1Corresponding author.

Contributed by the Dynamic Systems Division of ASME for publication in the JOURNAL OF DYNAMIC SYSTEMS, MEASUREMENT, AND CONTROL. Manuscript received May 2, 2016; final manuscript received December 4, 2016; published online April 13, 2017. Assoc. Editor: Tesheng Hsiao.

J. Dyn. Sys., Meas., Control 139(6), 061011 (Apr 13, 2017) (9 pages) Paper No: DS-16-1225; doi: 10.1115/1.4035456 History: Received May 02, 2016; Revised December 04, 2016

The problem of reversing vehicles with two trailers could be solved with a semi-autonomous assistance system for automatically steering the vehicle. In the literature found, no controllers have been implemented on a full-size vehicle with two trailers. In this paper, two simple path-tracking controllers are presented for automating the reversing of a “B-double” vehicle, consisting of a tractor and two trailers. One of the controllers is a heuristic “preview point” controller; the other uses a state feedback approach. The controllers steer the wheels on the front axle so as to stabilize the vehicle in reverse and control the path of the rearmost axle to follow a prescribed path. A tuning strategy is outlined where both controllers are tuned using the linear quadratic regulator and have the same closed-loop poles. The two controllers are implemented on a full-size B-double test vehicle. Experimental results are discussed, and the controller performances are evaluated against criteria. With the state feedback controller, the test vehicle was able to track target paths, consisting of a roundabout and a lane change, to within 50 mm.

FIGURES IN THIS ARTICLE
<>

Doubly articulated vehicles, such as the B-double (Fig. 1), are used in the road-freight industry. A B-double consists of a tractor unit, a special “B-trailer” which is a semitrailer with an additional coupling point on the rear, and a conventional semitrailer. The use of B-doubles can reduce fuel consumption (per freight task) by approximately 10% compared with conventional tractor–semitrailers, assuming they are fully laden [1].

A disadvantage of doubly articulated vehicles, including B-doubles, is the difficulty in reversing them. Reversing tends to be avoided where possible because they can only be reversed by highly skilled drivers [2]. The additional trailer increases the complexity of the reversing task and reduces the driver's visibility of the vehicle and the surrounding obstacles. A semi-autonomous system for reversing doubly articulated vehicles would prove useful. In order to introduce such a system, a path-tracking controller is required.

The problem of reversing an articulated vehicle to follow a desired path has been investigated in the literature. There are examples of reversing controllers for the multiple-trailer case [310]. In Ref. [3], a control law was defined between each consecutive trailer based on heading and heading rate errors. These control laws propagated down the vehicle from the rear trailer to the front unit where the actuation was applied. Simulation results were presented for a parallel parking maneuver.

A “virtual tractor” concept was used to develop controllers in Refs. [46]. This approach treats the last trailer like a virtual tractor and uses this to follow a desired path. It then applies a kinematic conversion between the last trailer and the tractor unit to calculate the tractor input commands. The controller proposed in Ref. [7] used the concept of “unicycle” control. It had an outer control loop for regulating the path tracking of the rear trailer. It used an inner loop transformation to convert this to control inputs for the tractor unit. All the three controllers were implemented on mobile robots with single axles and results were presented for short paths.

Fuzzy logic [8] has been used to design control strategies to complete the reversing task. Although very powerful in some applications, this approach requires a model or vehicle learning phase before a successful controller can be found. Since other examples in the literature prove that it is possible to complete the reversing task with analytical controller approaches, it seems unnecessary to use fuzzy logic for this application.

Bolzern et al. proposed two different methods in Refs. [9,10] using exact linearization with a “ghost vehicle” and input–output linearization. Both methods were compared in simulation, and it was found that the exact linearization approach performed better, although the controller design was more complex than that of the input–output linearization.

Overall, there is a lack of formal controller performance evaluation in the literature. Furthermore, no previous research has included the tire scrubbing characteristics of multiple-axle trailers on heavy vehicles. The most significant shortcoming in the literature, however, is that none of the approaches has been tested on a full-size heavy vehicle.

These shortcomings have been addressed in a previous paper [11], in which a simple path-tracking controller was implemented on vehicles with one, two, and three trailers. This paper aims to extend the work completed in Ref. [11], by introducing a second path-tracking controller and evaluating the performance of both controllers against a set of criteria. This detailed comparison was carried out on a B-double test vehicle (Fig. 1). The work presented here is part of a study investigating reversing of multiply articulated vehicles [12].

The objective of a path-tracking controller for reversing doubly articulated vehicles is to make the second trailer follow a desired path. In Fig. 2 (which shows a schematic of the vehicle), the point VA should follow the desired path. If the rear trailer has multiple axles, Winkler's approach [13] can be used to calculate the “equivalent” trailer wheelbase. The equivalent axle is then used to define the position of VA. This means that the controller can be implemented on articulated vehicles with trailers with single axles or multiple axles.

Performance Criteria.

In order to make a formal assessment of a path-tracking controller, a set of performance criteria was defined:

  • (i)Path offset of the equivalent axle on the rear trailer. This was the primary control objective. Root-mean-square (RMS) and maximum values were evaluated.
  • (ii)The “steer integral,” defined as the integral of absolute steer angle with respect to distance, |δ|ds (a measure of steer effort).
  • (iii)The RMS steer rate (the steer rate will have a limit based on the steering hardware of the vehicle).
  • (iv)The swept path of the vehicle. This is an envelope of the area the entire vehicle (including all the vehicle units) sweeps through as it maneuvers the path. It is the area generated by plotting each incremental vehicle position on top of each other. The width of this area relative to the path is calculated. RMS and maximum values were evaluated.

Preview Point Controller.

The “preview point” controller is shown schematically in Fig. 2 for a doubly articulated vehicle. A preview point (VP) is defined at a preview distance (Lp) behind the equivalent axle on the rear trailer. The lateral offset (yp) at this point is measured. Assuming the system is in steady-state, the radius of the desired path, Rp, is given by Display Formula

(1)Rp=Lp2+yp22yp

where Lp is the preview distance, and yp is the lateral offset at the preview point.

The corresponding second articulation angle (Γd2) was calculated using a lookup table generated from the vehicle equilibrium states for a given radius at point VA. The vehicle equilibrium states were calculated from the steady-state values of a vehicle model using a solver and setting the ordinary differential equation to zero. The radius of point VA was calculated from the equilibrium states using kinematics. To obtain the steady-state values of the vehicle in practice, a range of different steer angles were held at a constant speed and the resultant articulation angles and radii were measured. For practical reasons, this was done in the forward direction.

The desired second articulation angle (Γd2) was then fed into an articulation angle controller, defined by Display Formula

(2) δ=δd+K1(Γd1 Γ1)+K2(Γd2 Γ2)

where

δd=δ(s)/Γ2(s),   Γd1=Γ1(s)/Γ2(s)

Here, δ is the Ackerman average steer angle of the front axle, Γ1 is the articulation angle between the first and second vehicle units, Γ2 is the articulation angle between the second and third vehicle units, K1 is the gain associated with the first articulation angle, and K2 is the gain associated with the second articulation angle.  Γd1 is the desired first articulation angle and δd is the desired steer angle, both of which are equilibrium values corresponding to the desired second articulation angle, Γd2.

The corresponding control loop is illustrated in Fig. 3, showing the measurement of the preview offset, the calculation of the desired articulation angle, and the proportional controller to achieve the desired articulation angle. Proportional gains are applied to articulation angle errors, and the corresponding equilibrium steer angle is added. For a doubly articulated vehicle, the preview point controller has three tunable gains: the preview distance (Lp) and the two articulation angle gains (K1 and K2).

State Feedback Controller.

The state feedback controller includes feedback control on articulation angles, lateral offset, and heading error at the equivalent axle of the rear trailer. Some features of the controller are illustrated in Fig. 4 for a doubly articulated vehicle [11,12].

The steer angle was calculated as follows: Display Formula

(3)δ=δe+Kyaya+Kθa(θpθt)+KΓ1(Γe1 Γ1)+KΓ2(Γe2 Γ2)

Here, ya is the lateral offset from the equivalent axle to the path, θt is the heading of the rear trailer, and θp is the heading of the path. Γe1 is the first articulation angle, Γe2 is the second articulation angle, and δe is the steer angle which are all calculated from the equilibrium values corresponding to the radius of the path (using the same methods used for the preview point controller). Kya, Kθa, KΓ1, and KΓ2 are the controller gains corresponding to the axle offset, heading error, and first and second articulation angles, respectively.

Articulated vehicles have an inherent distance delay when traveling in reverse. This is because it takes some distance for the steering at the front of the vehicle to take effect at the rear trailer. The preview point controller compensates for this delay by using a preview point offset measurement. A similar approach was used for the state feedback controller. Instead of calculating the path curvature at the point where the axle offset is measured, PA in Fig. 4, the curvature was calculated at a point a certain “look-ahead” distance (LLA) along the path, PL. This curvature was then used to calculate the equilibrium steer angle and articulation angles used in the controller. The look-ahead distance allows some distance for the vehicle to reposition if the path curvature is changing but it has no effect on the steady-state performance.

The corresponding control loop is shown in Fig. 5, showing the measurement of the lateral and heading offsets at the equivalent axle of the rear trailer and the calculation of the equilibrium articulation angles corresponding to the path curvature. Proportional gains are applied to all the errors (lateral offset, heading offset, and articulation angle error), and the corresponding equilibrium steer angle is added. For a doubly articulated vehicle, the state feedback controller has five parameters to tune: lateral offset gain (Kya ), heading offset gain (Kθa), two articulation angle gains (KΓ1 and KΓ2), and the look-ahead distance (LLA).

Vehicle Modeling.

A nonlinear mathematical model of the vehicle was implemented in Matlab®. A schematic is shown in Fig. 6.

The following assumptions were made: it had five degrees-of-freedom (longitudinal, lateral, and yaw motion of the tractor unit and two articulation joints) and each axle was modeled as a single wheel, neglecting the roll and lateral load transfer effects (which are not significant at low speeds). It was assumed that the tractor unit (the first vehicle unit) was traveling at a constant speed and therefore that the driver would apply the necessary throttle to overcome any aerodynamic or rolling resistance that resulted from the maneuvers. This is an extension of the standard bicycle model to add two trailers.

The state vector, z, can be defined, where v1 and Ω1 are the lateral and rotational velocities at the center of mass of the tractor unit, as shown in Fig. 6Display Formula

(4)z=[v1Ω1Γ1Γ2Γ˙1Γ˙2]T

The velocities and accelerations at the center of mass of each vehicle unit can be defined in terms of the state vector, using kinematic relationships. The tire slip angles can then be calculated based on velocities at the tire and the steer angle (for the front axle). The lateral tire forces were calculated from the slip angles using a brush tire model, as detailed in Ref. [12].

Newton's second law was applied to the lateral forces of the tractor unit, the moments of the tractor unit about the hitch point, and both trailers about the hitch points. The articulation angle rates can be equated to provide six equations of motion, which can be rearranged as Display Formula

(5)fm(δ,z,z˙)=0,z˙=fd(δ,z)

where fm is a nonlinear function containing all the equations of motion and equating all the articulation angle rates, and fd is the rearranged nonlinear function to be used with the solver.

The vehicle model was linearized using Jacobian linearization to create a linear version of Eq. (5)Display Formula

(6)[M]Δz˙+[N]Δz+[H]Δδ=0

where

 [M]=fm/z˙,[N]=fm/z,and[H]=fm/δ

In order to represent the position of the vehicle in linear form, two location states were added to the linear vehicle model: the lateral position of the tractor unit CoG (y1)  and the heading of the tractor unit (θ1). These were used, along with vehicle geometry and articulation angles, to calculate the offsets at the rear axle.

Controller Tuning.

Both controllers were linearized (for the straight line case) to give a gain matrix, which could be multiplied by the linear state vector to calculate the steer angle. For a doubly articulated vehicle, both controller gain matrices could be written in the form Display Formula

(7)[K]=[00KL1KL200KLy1KLθ1]

where subscript L indicates the linearized controller.

Although the preview point controller has three tunable parameters, it linearizes to four gains in Eq. (7). The state feedback controller has five tunable parameters. However, when linearized about a straight line, the look-ahead distance, LLA, has no effect on the controller stability. Therefore, this simplifies to four parameters.

Combining Eqs. (6) and (7), the closed-loop system can be calculated Display Formula

(8)[A]=[M]1([N]+[H][K])

where [A] is the closed-loop matrix.

To ensure a fair comparison, both controllers were tuned with the same strategy such that the elements of the [K] matrix were the same. This meant the linear closed-loop poles were equal in both cases and the performance of both controllers about a straight line should be the same. The nonlinear behavior of the controllers during a maneuver, however, may differ. Therefore, the comparison was between the controller design rather than controller tuning.

A linear quadratic regulator (LQR) approach was used to tune the controllers. The cost function was defined as Display Formula

(9) J=0(wya2+δ2)dt

where w represents a weighting which can be used to tune how much emphasis is placed on axle offset versus how much steering is done, ya is the lateral offset from the equivalent axle to the path, and δ is the Ackerman average steer angle of the front axle.

A linear equivalent of Eq. (9) was derived Display Formula

(10)J=0(zT[Q]z+δT[R]δ)dt

Here,  [Q]=w[Cy]T[Cy], [ R ] = 1, where [Cy] is defined such that [Cy]z=yaL.

A Riccati equation was formed for the quadratic optimization problem and solved numerically in maltab® (this was done offline). The optimum control action was expressed as a full-state feedback gain matrix. The gain matrix [K] has some zero elements (corresponding to lateral velocity, yaw rate, and articulation angle rates). It was concluded that partial state feedback was adequate for this control task, since the states where no feedback is applied had low gains from the LQR calculation and their values are low during simulation. The nonzero elements of [K] were set to the corresponding elements of the gain matrix produced by the LQR calculation. A comparison between partial state feedback and full-state feedback was made in Ref. [12] and found to be negligible.

In order to achieve a specified gain matrix for both controllers, the individual controller gains had to be identified. For the state feedback controller, this was done using a state transformation matrix on the gain matrix [K]. For the preview point controller, this had to be done numerically because there were three parameters to tune (Lp, K1, and K2) for four elements of [K]. An algorithm was written to convert these four gains to the parameters needed to implement the preview point controller [12].

The look-ahead distance of the state feedback controller was calculated using frequency analysis on the part of the control loop relating to articulation angles. A time delay between desired and actual last articulation angle was calculated and then multiplied by the trailer speed to calculate the look-ahead distance.

The gains for both controllers are shown in Table 1 for a variety of weightings. These gains correspond to the parameters of the B-double test vehicle in Fig. 1, which has geometry given in Table 2.

Test Equipment.

Figure 7 shows a schematic of the test hardware including the sensors, actuators, and computers on the vehicle, along with their approximate locations and connections. A controller area network (CAN) bus using the ISO 11898 protocol was used to communicate digital signals between sensors on each vehicle unit and the global controller (shown as the “xPC” block). The global controller was operated using a laptop, connected via Ethernet.

A string potentiometer was used to measure the steer angle of the tractor unit's front wheels. The sensor was mounted to the underside of the chassis, and the string was attached to the front left steering radius arm. The articulation angles were measured using specially modified kingpins, which have angle sensors mounted on them, made by V.S.E. [14,15]. All the analog signals were low-pass filtered and digitized, using analog-to-digital converters (ADCs), and transmitted over the CAN bus to the controller. The zero positions of the string pot and articulation angle sensors were updated at the start of each test session to remove small signal offsets due to temperature and other drift.

A vehicle-based oxford technical solutions (OxTS) RT3022 (Global Navigation Satellite System and inertial sensor) [16] was used, with a base station and dual antennas, to measure position. The RT3022 was placed on the roof of the second trailer (tanker). The RT3022 signals were transmitted using a CAN bus. The offset between the heading of the RT3022 and the heading of the trailer was measured at the start of each test session by driving in a straight line and determining the difference between the heading calculated from the position and the measured heading.

The quoted accuracies for the RT3022 in the configuration used in these experiments are 200 mm for position and 0.1 deg for heading [16]. The measured accuracies were around 40 mm for latitude and longitude and 0.08 deg for heading. Line-tracking cameras were used to check the use of the RT3022 in assessing controller performance [12].

An Anthony Best Dynamics SR30 steering robot [17] was attached to the steering column (in place of the steering wheel) and used to actuate a demanded hand wheel angle. The robot was set to follow an external demand from the global controller via the CAN bus. The path-tracking controllers presented in Sec. 2 were used to determine the front axle steer angle of the tractor unit, required to track a path. The relationship between the hand wheel and the road wheel was measured, stored in a lookup table, and used to generate the hand wheel angle from the desired front axle steer angle.

Global Controller.

The control algorithms were implemented in real-time using the Matlab® “xPC target” toolbox. The global controller consisted of an “xPC unit,” which was a 500 MHz PC with the hard drive removed, setup to boot from a floppy disk drive. It had Softing AC2-PCI dual CAN bus cards in the PCI slots.

The global controller code was written in the Matlab® block diagram code environment, simulink, which could then be automatically compiled and downloaded onto the xPC unit. This compilation was done using the simulink coder (formerly known as “Real-Time Workshop”) to generate the C code and using the Microsoft Visual Studio C compiler to create an executable file.

A block diagram highlighting the main features of the global controller software is shown in Fig. 8.

The global position and heading of the equivalent axle on the rear trailer were calculated, using the RT3022 measurements and its known location on the vehicle. At the start of the run, a path was setup to start in alignment with the position and heading of the equivalent axle on the rear trailer. The offsets from the path were then calculated for the equivalent axle (and the preview point if applicable) and fed into the controller, along with articulation angles. The desired front axle steer angle was saturated with the known tractor steer limits and rate limited according to speed, to prevent any dry steering when the vehicle was stationary. The demand was converted to hand wheel angle and sent to the steering robot.

All the measured and computed quantities were logged. The code ran at a frequency of 100 Hz, which was compatible with all the hardware used and was sufficient to meet the bandwidth requirements of the controller.

The steady-state cornering equilibrium states of the vehicle were measured approximately every week during vehicle testing. It was thought that using a set of equilibrium values measured from the vehicle would give better performance than simulated values, particularly in steady-state cornering. The reason for regularly measuring the equilibrium states was to account for variations in temperature, humidity, and other features of the surface that affect the nonlinear tire [18]. A test procedure was created to efficiently obtain the vehicle equilibrium states by setting the steering robot to various steer angles and measuring the subsequent vehicle motion. In a commercial system, the equilibrium states could be estimated during the normal running of the vehicle.

Lane change and roundabout paths, shown in Figs. 9 and 10, respectively, were used as desired paths for the B-double test vehicle. The roundabout had a radius of 10 m, while the minimum instantaneous radius of the lane change was 20 m. Both paths had continuous second derivative of curvature. The paths were designed to ensure that the B-double could negotiate them without violating the steer rate limits (see Ref. [12] for details).

Tests were performed using both path-tracking controllers (preview point and state feedback), for a variety of LQR weightings (w in Eq. (4)) ranging from 0.1 to 10. The corresponding controller gains are shown in Table 1. The tests on the preview point controller for the roundabout path were only completed with weightings of 7 and 10 because at lower weightings, the preview distance becomes larger than 10 m, so the controller cannot work with a path of radius 10 m.

Tests were performed with the vehicle traveling at a constant speed of −1 m/s. Three repeat tests were performed for each test configuration (path type, controller type, and weighting). The tests were found to be repeatable apart from small random errors (see Ref. [12]) and so they were averaged with respect to distance.

Experimental Results.

Average axle positions are shown for the state feedback and the preview point controller in Figs. 9 and 10 for the lane change and roundabout maneuvers, respectively. These tests were conducted with weightings of 5 for the lane change and 7 for the roundabout path. In both cases, the state feedback controller tracked the path well but the preview point controller showed noticeable deviations from the path.

For the same weightings (5 and 7), comparisons are presented between the state feedback and the preview point controller in Figs. 11 and 12 for the lane change and roundabout maneuvers, respectively. The results show: (a) the offset of the equivalent axle on the rear trailer, (b) front axle steer angle, (c) front axle steer angle rate, and (d) swept path. The measured positions and articulation angles, along with the vehicle geometry in Table 2, were used to calculate the swept path of the vehicle for the test run (this was postprocessed from the position data).

On both maneuvers, the axle offsets are larger for the preview point controller, while the state feedback controller uses more steer effort, as shown in the steer angle (b) and steer rate (c) plots. The steer angles are smoother for the preview point controller, which suggests that this controller is “cutting the corners” of the desired path. This is confirmed by the swept path comparison shown in Fig. 11(d), which shows that the swept path of the preview point controller is significantly less than the swept path for the state feedback controller on the lane change maneuver. For the roundabout maneuver (shown in Fig. 12(d)), there is less difference between the swept paths for the two controllers but the preview point controller performs slightly better in this aspect.

A significant feature of these experimental results is the presence of small-amplitude oscillations (seen in the axle offsets and steer angles). The oscillations had an amplitude of approximately 50–100 mm, which is far less than a truck tire width (approximately 400 mm). All the closed-loop experimental results from this research show this phenomenon, which is particularly noticeable in steady-state parts of maneuvers. A thorough investigation into the root cause of these oscillations was conducted in Ref. [12], which included simulating tire relaxation length. It was found that a closed-loop system pole was being driven by lateral tire force disturbances (probably caused by cross-slope on the rough test track surface), with delays between axles. With some retuning of controller gains, it was possible to reduce the size of the oscillations slightly.

Performance Criteria.

In Table 3, the results shown in Figs. 13(a) and 13(b) are summarized in terms of the performance criteria defined in Sec. 2.1. The values of each performance metric were calculated individually for each test run and then averaged for the three repeats. The metrics were calculated in this way to remove any effect of averaging the time series data (as used for plotting Figs. 11 and 12), which would have a favorable effect on the performance metrics.

Table 3 shows a significant difference between the maximum and RMS values of the axle offsets generated by the state feedback and preview point controllers. For both paths, the offset metrics are increased by a factor of 3–5 if the preview point controller is used instead of the state feedback controller. The steer integrals are comparable for the roundabout maneuver for both controllers, but for the lane change the steer integral for the state feedback controller is 20% higher than that for the preview point controller. The RMS steer rate for the state feedback controller is almost 50% higher than that for the preview point controller. The swept path RMS values are comparable for both controllers, but the maximum swept path is 10–20% higher for the state feedback controller.

The results from the experiments using both controllers with various weightings are summarized in Figs. 13(a) and 13(b) for two of the performance criteria. Figure 13(a) shows the RMS offset of the rear trailer equivalent axle for all the four cases (two controllers and two paths) with weightings ranging from 0.1 to 10. The general trend shown is that axle offsets decrease as the weighting increases. This is an expected trend, also seen in simulation [12]. An exception is that the state feedback controller shows a small increase in RMS axle offset for weightings greater than 5. This could be due to an increased sensitivity to disturbances and sensor noise when higher gains are used.

In Fig. 13(a), there are two distinct groups: one group for the preview point controller on both paths and one for the state feedback controller on both paths. This shows that the state feedback controller performs significantly better than the preview point controller on both paths. Interestingly, the axle offsets achieved by the state feedback controller on both paths are similar.

Figure 13(b) shows the RMS steer rate for all the four cases (two controllers and two paths) with weightings ranging from 0.1 to 10. The preview point controller requires lower RMS steer rates than the state feedback controller, on both paths. In general, the RMS steer rates increase with weighting. This indicates a trade-off between axle offset and steer effort. However, the trend is less clear than that seen for the axle offsets. This is because the steer rate was calculated by differentiating the front axle steer angle measurements with respect to time which introduced some noise due to sensor noise and quantization.

Figures 13(a) and 13(b) both show some overlap between the performance of the controllers. In particular, the preview point controller on the roundabout path with a weighting of 10 has a slightly lower RMS axle offset than the state feedback controller with a weighting of 0.1. The RMS steer rate of the state feedback controller when the weighting is 1 or 0.1 on the roundabout path drops below that of the preview point controller with a weighting of 10. Therefore, on the roundabout path, the state feedback controller with a weighting of 1 is able to outperform the preview point controller with a weighting of 10 in terms of RMS axle offset and RMS steer rate.

Two path-tracking controllers, “state feedback” and preview point, were implemented on a B-double test vehicle and tested on roundabout and lane change paths and the following conclusions were made:

  • (i)The preview point controller exhibited larger path errors but used less steer input and had a lower swept path than the state feedback controller.
  • (ii)With the state feedback controller, the B-double was able to track the roundabout and lane change paths to within 50 mm.
  • (iii)With the preview point controller, the B-double was able to track the roundabout and lane change paths to within 220 mm.
  • (iv)There is a tradeoff between axle offset and steer effort: RMS axle offsets decrease and RMS steer rates generally increase as the LQR weighting is increased.
  • (v)All the experimental results show the presence of small steady-state oscillations (less than one tire width), due to a closed-loop system pole being driven by vehicle disturbances.

This research was funded by the Engineering and Physical Sciences Research Council (EPSRC) and Volvo Trucks through an Industrial CASE award. The authors would like to acknowledge Leo Laine and Carl-Johan Hoel from Volvo Trucks for their collaboration and contributions to the research. The authors would also like to acknowledge Denby Transport for their loan of the “Extra” Eco-Link B-trailer for use in vehicle testing. The members of the CVDC who supported the work in this paper. At the time of writing, the Consortium consisted of the University of Cambridge with the following partners from the heavy vehicle industry: Anthony Best Dynamics, Camcon, Denby Transport, Firestone Air Springs, GOODYEAR DUNLOP, Haldex, Motor Industry Research Association, SDC Trailers, SIMPACK, Tinsley Bridge, Tridec, Volvo Trucks, and Wincanton.

  • a =

    distance from CoG to front axle of tractor unit or front hitch point of trailer (m)

  • b =

    distance from CoG to rear axle of tractor unit or first axle of trailer (m)

  • c =

    distance from rear axle of tractor unit or first axle of trailer to rear hitch point (m)

  • J =

    LQR cost function

  • K =

    controller gain

  • l =

    equivalent wheelbase of vehicle unit (m)

  • Lp =

    preview distance (m)

  • LLA =

    look-ahead distance for state feedback controller (m)

  • PA =

    effective axle of rear trailer point on path

  • PL =

    look-ahead point on path

  • Rp =

    radius for preview point controller calculation (m)

  • s =

    distance along the path (m)

  • VA =

    effective axle point of rear trailer

  • VP =

    preview point of rear trailer

  • w =

    cost function weighting

  • ya =

    lateral offset of the effective axle of the rear trailer to the desired path (m)

  • yp =

    lateral offset of the preview point to the desired path (m)

  • Γ =

    articulation angle (rad)

  • δ =

    tractor unit front axle steer angle (rad)

  • θ =

    heading angle of vehicle unit (rad)

  • θp =

    heading angle of path (rad)

 Subscripts
  • d =

    demanded value or corresponding to a demanded value

  • e =

    equilibrium value

  • y =

    corresponding to the lateral path error

  • Γ =

    corresponding to the articulation angle error

Odhams, A. M. C. , Roebuck, R. L. , Lee, Y. J. , Hunt, S. W. , and Cebon, D. , 2010, “ Factors Influencing the Energy Consumption of Road Freight Transport,” Proc. Inst. Mech. Eng. Part C, 224(9), pp. 1995–2010. [CrossRef]
Kjell, M. , and Westerlund, K. R. , 2009, “ Feasibility of Longer Combination Vehicles,” Masters dissertation, Chalmers University of Technology, Gothenburg, Sweden.
Michalek, M. , 2011, “ Geometrically Motivated Set-Point Control Strategy for the Standard N-Trailer Vehicle,” Intelligent Vehicles (IV) Symposium, June 5–9, Baden-Baden, Germany, pp. 138–143.
Morales, J. , Martinez, J. L. , Mandow, A. , and Garcia-Cerezo, A. J. , 2013, “ Steering the Last Trailer as a Virtual Tractor for Reversing Vehicles With Passive On- and Off-Axle Hitches,” IEEE Trans. Ind. Electron., 60(12), pp. 5729–5736. [CrossRef]
Morales, J. , Mandow, A. , Martínez, J. , Reina, A. J. , and García-Cerezo, A. , 2013, “ Driver Assistance System for Passive Multi-Trailer Vehicles With Haptic Steering Limitations on the Leading Unit,” Sensors, 13(4), pp. 4485–4498. [CrossRef] [PubMed]
Sekhavat, S. , Lamiraux, F. , Laumond, J. P. , Bauzil, G. , and Ferrand, A. , 1997, “ Motion Planning and Control for Hilare Pulling a Trailer: Experimental Issues,” IEEE International Conference on Robotics and Automation (IRCA), Albuquerque, NM, pp. 3306–3311.
Michałek, M. A. , 2014, “ Highly Scalable Path-Following Controller for N-Trailers With Off-Axle Hitching,” Control Eng. Pract., 29, pp. 61–73. [CrossRef]
Tanaka, K. , Taniguchi, T. , and Wang, H. O. , 1999, “ Trajectory Control of an Articulated Vehicle With Triple Trailers,” IEEE International Conference on Control Applications, Kohala Coast, HI, Aug. 22–27.
Bolzern, P. , DeSantis, R. M. , Locatelli, A. , and Masciocchi, D. , 1998, “ Path-Tracking for Articulated Vehicles With Off-Axle Hitching,” IEEE Trans. Control Syst. Technol., 6(4), pp. 515–523. [CrossRef]
Bolzern, P. , DeSantis, R. M. , and Locatelli, A. , 2001, “ An Input–Output Linearization Approach to the Control of an n-Body Articulated Vehicle,” ASME J. Dyn. Syst. Meas. Control, 123(3), pp. 309–316. [CrossRef]
Rimmer, A. J. , and Cebon, D. , 2016, “ Theory and Practice of Reversing Control on Multiply—Articulated Vehicles,” Proc. Inst. Mech. Eng. Part D, 230(7), pp. 899–913.
Rimmer, A. J. , 2014, “ Autonomous Reversing of Multiply-Articulated Heavy Vehicles,” Ph.D. dissertation, University of Cambridge, Cambridge, UK.
Winkler, C. B. , 1998, “ Simplified Analysis of the Steady-State Turning of Complex Vehicles,” Veh. Syst. Dyn., 29(3), pp. 141–180 [CrossRef]
VSE, 2014, “Weber-Hydraulik VSE,” Vehicle Systems Engineering B.V., Veenendaal, The Netherlands, accessed Aug. 1, 2014, http://www.v-s-e.com/en
VSE, 2012, “Product Information ETS for Trailers,” V.S. Engineering.
O.T.S., 2010, “RT Inertial and GPS Measurement Systems: User Guide,” O.T.S. Ltd., Upper Heyford, UK.
Anthony Best Dynamics, 2012, “Steering Robot SR Series User Guide,” Anthony Best Dynamics Ltd., Bradford on Avon, UK.
Pacejka, H. B. , 2012, Tire and Vehicle Dynamics, Butterworth-Heinemann, Oxford, UK.
Copyright © 2017 by ASME
View article in PDF format.

References

Odhams, A. M. C. , Roebuck, R. L. , Lee, Y. J. , Hunt, S. W. , and Cebon, D. , 2010, “ Factors Influencing the Energy Consumption of Road Freight Transport,” Proc. Inst. Mech. Eng. Part C, 224(9), pp. 1995–2010. [CrossRef]
Kjell, M. , and Westerlund, K. R. , 2009, “ Feasibility of Longer Combination Vehicles,” Masters dissertation, Chalmers University of Technology, Gothenburg, Sweden.
Michalek, M. , 2011, “ Geometrically Motivated Set-Point Control Strategy for the Standard N-Trailer Vehicle,” Intelligent Vehicles (IV) Symposium, June 5–9, Baden-Baden, Germany, pp. 138–143.
Morales, J. , Martinez, J. L. , Mandow, A. , and Garcia-Cerezo, A. J. , 2013, “ Steering the Last Trailer as a Virtual Tractor for Reversing Vehicles With Passive On- and Off-Axle Hitches,” IEEE Trans. Ind. Electron., 60(12), pp. 5729–5736. [CrossRef]
Morales, J. , Mandow, A. , Martínez, J. , Reina, A. J. , and García-Cerezo, A. , 2013, “ Driver Assistance System for Passive Multi-Trailer Vehicles With Haptic Steering Limitations on the Leading Unit,” Sensors, 13(4), pp. 4485–4498. [CrossRef] [PubMed]
Sekhavat, S. , Lamiraux, F. , Laumond, J. P. , Bauzil, G. , and Ferrand, A. , 1997, “ Motion Planning and Control for Hilare Pulling a Trailer: Experimental Issues,” IEEE International Conference on Robotics and Automation (IRCA), Albuquerque, NM, pp. 3306–3311.
Michałek, M. A. , 2014, “ Highly Scalable Path-Following Controller for N-Trailers With Off-Axle Hitching,” Control Eng. Pract., 29, pp. 61–73. [CrossRef]
Tanaka, K. , Taniguchi, T. , and Wang, H. O. , 1999, “ Trajectory Control of an Articulated Vehicle With Triple Trailers,” IEEE International Conference on Control Applications, Kohala Coast, HI, Aug. 22–27.
Bolzern, P. , DeSantis, R. M. , Locatelli, A. , and Masciocchi, D. , 1998, “ Path-Tracking for Articulated Vehicles With Off-Axle Hitching,” IEEE Trans. Control Syst. Technol., 6(4), pp. 515–523. [CrossRef]
Bolzern, P. , DeSantis, R. M. , and Locatelli, A. , 2001, “ An Input–Output Linearization Approach to the Control of an n-Body Articulated Vehicle,” ASME J. Dyn. Syst. Meas. Control, 123(3), pp. 309–316. [CrossRef]
Rimmer, A. J. , and Cebon, D. , 2016, “ Theory and Practice of Reversing Control on Multiply—Articulated Vehicles,” Proc. Inst. Mech. Eng. Part D, 230(7), pp. 899–913.
Rimmer, A. J. , 2014, “ Autonomous Reversing of Multiply-Articulated Heavy Vehicles,” Ph.D. dissertation, University of Cambridge, Cambridge, UK.
Winkler, C. B. , 1998, “ Simplified Analysis of the Steady-State Turning of Complex Vehicles,” Veh. Syst. Dyn., 29(3), pp. 141–180 [CrossRef]
VSE, 2014, “Weber-Hydraulik VSE,” Vehicle Systems Engineering B.V., Veenendaal, The Netherlands, accessed Aug. 1, 2014, http://www.v-s-e.com/en
VSE, 2012, “Product Information ETS for Trailers,” V.S. Engineering.
O.T.S., 2010, “RT Inertial and GPS Measurement Systems: User Guide,” O.T.S. Ltd., Upper Heyford, UK.
Anthony Best Dynamics, 2012, “Steering Robot SR Series User Guide,” Anthony Best Dynamics Ltd., Bradford on Avon, UK.
Pacejka, H. B. , 2012, Tire and Vehicle Dynamics, Butterworth-Heinemann, Oxford, UK.

Figures

Grahic Jump Location
Fig. 1

B-double test vehicle: The Denby extra ecolink B-trailer was loaned by Denby transport. The other vehicle units are part of the CVDC test vehicle fleet. Distances shown between the front axle and the hitch point for the tractor unit, hitch-to-hitch for the B-trailer, and hitch to equivalent rear axle for the tanker.

Grahic Jump Location
Fig. 2

Vehicle diagram illustrating preview point controller, shown here for a doubly articulated vehicle

Grahic Jump Location
Fig. 3

Control loop for preview point controller shown for a doubly articulated vehicle. Quantities are defined in Sec. 2.2.

Grahic Jump Location
Fig. 4

Vehicle diagram illustrating state feedback controller, for a doubly articulated vehicle

Grahic Jump Location
Fig. 5

Control loop for a state feedback controller shown for a doubly articulated vehicle. Here, κ denotes the curvature of the path and the other quantities are defined in Sec. 2.3.

Grahic Jump Location
Fig. 6

Vehicle diagram showing dimensions and velocities for doubly articulated vehicle

Grahic Jump Location
Fig. 7

Diagram of test equipment for B-double test vehicle (vehicles separated for clarity)

Grahic Jump Location
Fig. 8

Block diagram representing global controller software code. The implementation of the “controller” block can be either of the two paths following controllers (preview point or state feedback).

Grahic Jump Location
Fig. 9

Lane change maneuver showing the positions of the equivalent axle of the B-double rear trailer when state feedback and preview point controllers are used

Grahic Jump Location
Fig. 10

Roundabout maneuver showing the positions of the equivalent axle of the B-double rear trailer when state feedback and preview point controllers are used

Grahic Jump Location
Fig. 11

Comparison of state feedback and preview point controllers implemented on B-double for lane change path, tuned with LQR weighting (w) of 5, showing (a) rear trailer effective axle lateral offset, (b) front axle steer angle, (c) first articulation angle, (d) second articulation angle, (e) front axle steer rate, and (f) vehicle swept path. Gray lines indicate the state feedback controller, and black lines indicate the preview point controller.

Grahic Jump Location
Fig. 12

Comparison of state feedback and preview point controllers implemented on B-double for roundabout path, tuned with LQR weighting (w) of 5, showing (a) rear trailer effective axle lateral offset, (b) front axle steer angle, (c) first articulation angle, (d) second articulation angle, (e) front axle steer rate, and (f) vehicle swept path. Gray lines indicate the state feedback controller, and black lines indicate the preview point controller.

Grahic Jump Location
Fig. 13

Summary of B-double experimental results when preview point and state feedback controllers are implemented on lane change and roundabout paths. LQR weighting (w) ranged from 0.1 to 10. (a) RMS offsets of the rear trailer equivalent axle and (b) RMS steer rates.

Tables

Table Grahic Jump Location
Table 1 Controller gains implemented on B-double test vehicle
Table Footer NoteaThe look-ahead distance quoted corresponds to a trailer speed of −1 m/s.
Table Grahic Jump Location
Table 2 Vehicle geometry of B-double test vehicle
Table Grahic Jump Location
Table 3 Summary of performance criteria metrics for B-double

Errata

Discussions

Some tools below are only available to our subscribers or users with an online account.

Related Content

Customize your page view by dragging and repositioning the boxes below.

Related Journal Articles
Related eBook Content
Topic Collections

Sorry! You do not have access to this content. For assistance or to subscribe, please contact us:

  • TELEPHONE: 1-800-843-2763 (Toll-free in the USA)
  • EMAIL: asmedigitalcollection@asme.org
Sign In