Abstract

This paper presents the design and analysis of a predictive ecological control strategy for a heavy-duty truck that achieves substantial fuel savings while maintaining safe following distances in the presence of traffic. The hallmark of the proposed algorithm is the fusion of a long-horizon economic model predictive controller (MPC) for ecological driving with a command governor (CG) for safe vehicle following. The performance of the proposed control strategy was evaluated in simulation using a proprietary medium-fidelity Simulink model of a heavy-duty truck. Results show that the strategy yields substantial fuel economy improvements over a baseline, the extent of which are heavily dependent on the horizon length of the CG. The best fuel and vehicle-following performance are achieved when the CG horizon has a length of 20–40 s, reducing fuel consumption by 4–6% when compared to a Gipps car-following model.

1 Introduction

Heavy-duty trucks are responsible for 23% of transportation-related CO2 emissions in the U.S. (see Ref. [1]). There have been many attempts in both government and industry to increase the fuel economy of heavy duty trucks (see Ref. [2]). Current projections forecast freight tonnage increasing 1.4% per year for the next few decades (see Ref. [3]). In order for heavy-duty trucks to achieve better fuel economy while meeting the increasing demand for freight transport, predictive ecological vehicle control technologies offer a promising solution. The overarching objective of the research explored in this paper is to fuse fuel efficiency with safe vehicle-following for heavy-duty vehicles. This requires the consideration of a lengthy horizon for the purpose of fuel efficiency, which requires consideration of a much shorter horizon for safe vehicle following.

For light-duty passenger vehicles, a substantial body of literature has studied the problems of velocity trajectory optimization for fuel efficiency and following constraint satisfaction, both in isolation and in combination. When used for velocity trajectory optimization alone, these control strategies are referred to as ecological cruise control (ECC). In particular, model predictive control (MPC) has been widely used in online ECC strategies (see Refs. [4] and [5]), due to MPC's inherent ability to consider economic performance objectives while explicitly enforcing constraints. Furthermore, multiple papers have incorporated following distance considerations and penalties within MPC formulations, thereby achieving ecological vehicle following. Such control strategies are termed ecological adaptive cruise control (Eco-ACC) strategies. The authors of Ref. [6] designed an Eco-ACC such that the MPC objective function approximated fuel consumption while adding penalties to the objective function to promote driver comfort and safety. Simulation results from Ref. [6] indicated that Eco-ACC improved the fuel economy in comparison with typical ACC. In Refs. [7] and [8], the MPC objective function was designed to improve ecological driving by penalizing nonsmooth acceleration profiles. Additionally, in Refs. [7] and [8], hard constraints on acceptable bounds for various desired vehicle-following qualities (such as vehicle-following distance, maximum jerk, and relative velocity) were incorporated and softened when necessary to ensure feasibility.

The aforementioned Eco-ACCs were designed for passenger vehicles, which benefit substantially through MPC-based Eco-ACC strategies with horizons of hundreds of meters or less. On the other hand, due to their inertial properties, it has been demonstrated in Ref. [9] that heavy-duty trucks only begin to see near-full benefits of ECC under horizon lengths greater than 2000 m. Consequently, MPC-based ECCs designed for heavy-duty trucks in Refs. [1012] rely on horizon lengths of 2000 m or more. Implementing MPC-based Eco-ACCs on heavy-duty trucks has recently been explored in Refs. [13] and [14]. Typically, MPC-based Eco-ACCs explicitly enforce vehicle-following constraints within the MPC, which is implemented at a time-step of 100–200 ms to account sudden changes in the behavior of the lead vehicle [15]. Due to the limited computational resources on a typical electronic control unit, an MPC-based Eco-ACC that explicitly enforces vehicle-following constraints implemented on a heavy-duty truck would require a shorter horizon (therefore sacrificing ecological performance) to ensure the MPC is real-time feasible (see Ref. [16]). To avoid the above tradeoff between ecological performance and real-time feasibility, the MPC-based Eco-ACCs in Refs. [13] and [14] implemented a proportional plus derivative distance-keeping controller that heuristically maintained safe vehicle following, in parallel to an MPC-based ECC designed for a heavy-duty truck. While solving all issues relating to computational complexity, the plus derivative distance-keeping controller does not provide any guarantees of constraint satisfaction. Indeed, to the best of our knowledge, an MPC-based Eco-ACC designed for a heavy-duty truck that explicitly enforces vehicle-following constraints has yet to be investigated in the literature.

To address the aforementioned challenges, we propose an Eco-ACC that decouples ecological driving and distance keeping through the cascade of an MPC with a command governor (CG). A CG is an add-on scheme that alters the reference to a closed-loop stable system (see Ref. [17]). CGs are predictive control schemes used solely to enforce constraints. Compared to MPC, CGs are less computationally expensive (see Ref. [18]) and can consequently be implemented with much smaller time steps than MPC, at the expense of only being able to enforce constraints (rather than additionally managing competing performance objectives, which is accomplished by MPC).

In this work, we present an Eco-ACC, first introduced at a basic level in our conference publication [19], that implements an upper level MPC-based ECC cascaded with a lower level command governor. Such an inner loop command governor, which cascades an economic MPC, is new to the Eco-ACC literature. A conceptual diagram of this Eco-ACC strategy is shown in Fig. 1. The upper level MPC-based ECC, which is fused with an offline dynamic programing (DP) optimization, was originally developed in Ref. [11]. The benefit of fusing an offline DP with online MPC is that the MPC is able to utilize global knowledge of the route that is accounted for in the offline DP solution. This is achieved by using the global and coarsely gridded DP solution to serve as an initial guess for the MPC optimization, and by penalizing large deviations from the DP solution. The DP solution is calculated offline, producing an energy-optimal longitudinal force profile (and corresponding velocity profile) that is optimal with respect to the route topology but does not consider traffic or fine-scale terrain variations. In order for the DP solution to be referenced in real-time by the MPC algorithm, the DP-optimized velocity profile is indexed with respect to position on the route. By indexing the profile with respect to route position, the DP-optimized velocity profile will remain usable by the MPC even in the presence of traffic events that necessitate an altered velocity profile over some portion of the route (thereby leading to the ego vehicle reaching particular points on the route at different times than were anticipated by the DP optimization). The upper level MPC reoptimizes the control sequence to minimize energy expenditure over a receding horizon, introducing a feedback mechanism to account for disturbances, such as when the ego vehicle deviates significantly from the DP optimal solution due to traffic. The MPC in this work minimizes the energy expended as a surrogate for fuel consumption, as is done in Ref. [11], and utilizes an energy-based affine model of the longitudinal dynamics, rendering the optimization convex. The CG maintains distance-keeping constraints by adjusting the output of the upper level MPC, thereby modulating the wheel force command passed to the lower level powertrain controller. By design, the CG only adjusts the output of the upper level MPC the minimum amount necessary to satisfy vehicle-following constraints. The block diagram of this control strategy is shown in Fig. 2. Since the CG enforces distance-keeping constraints, the MPC can be implemented at a much longer time-step, and was shown in Ref. [13] to be real-time feasible when using a horizon length of 2000 m. The CG is formulated such that two vehicle-following constraints are enforced:

  1. A desired minimum following distance that can be momentarily infringed upon so long as the ego vehicle ultimately backs off toward this following distance.

  2. A minimum safe following distance, which is less than the desired minimum following distance, that must be enforced at all times.

This paper greatly extends our initial conference publication [19], through the presentation of a performance analysis under a wide array of controller parameters. Specific contributions of this paper, relative to those of our earlier conference paper [19], include:

  • The utilization of an upper level MPC that is designed for real-time implementation in heavy-duty trucks;

  • An analysis of the effect of the CG horizon on fuel economy for various real-world trucking routes and trailer loads; and

  • The consideration of drivability as an additional metric against which performance is evaluated.

2 Vehicle Model

2.1 Longitudinal Vehicle Model.

A proprietary medium fidelity Simulink model of a heavy-duty truck was used to run simulations of the cascaded MPC and CG-based Eco-ACC algorithm in highway driving scenarios with traffic. The initial offline optimization and the CG use a second-order control-oriented model of the longitudinal dynamics, where the state variable, x, is defined as
(1)

where xego and vego denote the position and velocity of the ego vehicle, respectively. The simplified control-oriented model is implemented in discrete time, where the time-step is given by t, as

(2b)

Here, u(t) is the propulsive force applied to the road through the wheel. The terms Fdrag,Fgrav, and Froll are external forces on the vehicle arising from aerodynamic drag, gravity, and rolling resistance, respectively. These external forces are defined as follows:
(3)
(4)
(5)

Parameters ρ, Cd, Aref, m, g, and Crr are defined as the air density, aerodynamic drag coefficient, reference area, ego vehicle mass, acceleration of gravity, and rolling resistance coefficient. The variable θ(xego) represents road grade as a function of the ego vehicle position along the route.

2.2 Fuel Consumption Model.

The fuel consumption model presented here was used by the initial offline optimization (whereas in simulations, the proprietary heavy-duty truck model was used to characterize the fuel consumption rate). A brake-specific fuel consumption (BSFC) map of a heavy duty truck, provided by Volvo, was used to model the fuel consumption rate, Rfuel, as follows:
(6)
The BSFC map is dependent on engine speed and engine torque, denoted as ωeng and Teng, respectively. Peng refers to the engine power and was calculated using
(7)
(8)
(9)

where ηdl,τgrτax, and rwh are the driveline efficiency, gear ratio, drive axle gear ratio, and wheel radius. For the initial offline optimization, the gear was chosen using a static shift map, which selected the gear that minimized BSFC for a given u and v.

2.3 Energy-Based Vehicle Model.

The MPC uses a first-order energy-based model of the longitudinal dynamics of the ego vehicle. The dynamics are discretized in distance, where k corresponds to a discrete position along the route. The discrete energy-based model is given by
(10)
where the state is the kinetic energy of the ego vehicle, Ekin. The terms Emech and Ebrake represent the propulsive energy expended and the energy dissipated due to braking, respectively, over distance step k. Emech and Ebrake are the control inputs to the model. The terms Emech and Ebrake are related to the propulsive force, u, via
(11)
(12)
Eenv(k) represents the total loss in kinetic energy over one distance step, Δx, due to the combination of aerodynamic losses, rolling resistance losses, and increases in potential energy due to road grade. Thus, this quantity is expressed as
(13)

3 Control Strategy

The Eco-ACC strategy presented in this paper utilizes an initial global, coarsely discretized, offline DP optimization of the ego vehicle's velocity with respect to road terrain. These results of the offline optimization provide a reference velocity profile, indexed by position on the route, for the online MPC. Specifically, this reference is used to set tracking error penalties on deviations from the offline optimized velocity trajectory over the prediction horizon of the MPC, which implements a control sequence that minimizes the energy expended by the ego vehicle. The control signal from the MPC is fed into a CG, which adjusts the control signal, when necessary, to enforce distance-keeping constraints for a nonconnected lead vehicle.

3.1 Initial Offline Optimization.

The initial offline optimization is performed using DP for a coarse discretization of position (xego). For a given destination, xdest, and desired trip time, Tdes,trip (which can be prescribed by the driver or fleet operator, and is assumed to be feasible), the offline optimization finds the optimal control sequence, uDP*, that minimizes fuel consumption. Trip time is discretized into NDP time steps, each having length ΔtDP. The optimal sequence, uDP*, is calculated as follows:
(14a)
(14b)
(14c)
(14d)

and the vehicle dynamics defined in Eq. (2). Rfuel is the fuel consumption rate, which depends on the applied wheel force. The terms vmin(xego) and vmax(xego) are minimum and maximum velocity limits, respectively, where vmax is determined by the speed limit for the given route at position xego, and vmin is 70% of vmax. The terms umin and umax are the minimum and maximum limits of applied wheel force, respectively, and are set by the performance capabilities of the simulated heavy-duty truck.

3.2 Model Predictive Controller Formulation.

The decision variables for the MPC strategy are the propulsive energy expended, Emech, and the energy lost due to braking, Ebrake. A receding distance horizon is discretized into NMPC distance steps, each of length ΔxMPC. The MPC prescribes a propulsive wheel force that is the net result of the optimized engine and braking effort dictated by Emech*, and Ebrake*, respectively. As is standard for MPC, the first step of each optimized control sequence, denoted as uMPC, is implemented
(15)

and the optimization is repeated over the receding time horizon at the next position step, k +1. The offline optimal control sequence, uDP*, implicitly defines optimal position and velocity sequences, denoted by xDP* and vDP*, respectively. These optimal position and velocity sequences are utilized by the MPC in two ways:

  1. The position and velocity sequences are used to formulate tracking error penalties for the MPC optimization.

  2. The DP solution, uDP*, is used as an initial guess for the MPC optimization.

The online optimization addressed by the MPC is formulated as
(16a)
(16b)
(16c)
(16d)
(16e)
where
(17a)
(17b)
The notation (i|k) refers to the ith step within the prediction horizon for an optimization that is performed at step k. The terms Ekinmax and Ekinmax in Eq. (16c) are the minimum and maximum admissible kinetic energies of the ego vehicle, as dictated by vmin(i|k) and vmax(i|k), respectively. The MPC cost function penalizes the tracking error between the predicted kinetic energy profile and the target kinetic energy profile, EDP, that is dictated by the optimal DP solutions xDP* and vDP* over the MPC horizon, resulting in the following MPC cost function
(18)

where λb, and λd are tuning weights. By penalizing Emech and Ebrake, the MPC minimizes the energy put into the system in order to overcome the energy expended due to aerodynamic drag, rolling resistance and road grade, as dictated by constraint. By penalizing Ebrake (in addition to Emech), the MPC strategy avoids energy loss due to unnecessary braking events that must be recovered afterward through mechanical work in order to maintain the desired kinetic energy. Increasing λd prioritizes how strictly the MPC tracks the offline DP trajectory and completes the trip by the desired trip time, Tdes,trip. Increasing λb prioritizes avoiding unnecessary braking, thereby further improving fuel economy. Values for λb and λd are given Sec. 4.1.

3.3 Command Governor Formulation.

The aforementioned DP and MPC formulations work together to minimize fuel consumption without sacrificing trip time. However, they do not address vehicle-following constraints or the drivability implications associated with these constraints (e.g., high-jerk events associated with vehicle cut-ins). The lower level CG is designed specifically for addressing these concerns. Traditionally, reference and command governors are used to enforce constraints by modifying the reference input to an already stable system. In particular, reference and command governors modify the reference to a value that, if held constant, would satisfy all constraints over all future time. The set of all originating states and constant inputs that satisfy constraints is commonly referred to as the maximal output admissible set. Typically, reference and command governors can always adjust the reference such that the input and current state are within the maximal admissible set, a property referred to as recursive feasibility. In realistic vehicle-following scenarios, however, there is no constant input that can be guaranteed with certainty to satisfy distance-keeping constraints over all time. This is the case for two reasons:

  1. The future velocity profile of the lead vehicle is unknown; thus, the future constraints are unknown.

  2. If the velocity profiles of the lead vehicles vary significantly (i.e., the disturbances are large), no constant input could be applied for the duration of the trip that upholds distance-keeping constraints and satisfies upper and lower speed bounds.

A recovery reference governor, developed in Ref. [20], can recover a closed-loop system when an unmodeled disturbance causes a constraint violation; however it is applied to linear systems. Additionally, conventional reference and command governor theory places the governor outside of the feedback loop (see Ref. [21]), adjusting only the reference signal of the closed-loop system. However, the upper level MPC in this work has an economic objective function, i.e., the MPC does not track a reference. For us to enforce vehicle-following constraints, we have chosen to place our command governor inside the feedback loop, cascaded from the upper level MPC. Though reference and command governor theory for placing the governor inside the control loop has only thus far resulted in recursive feasibility results for a set of specific controller and plant configurations (see Refs. [22] and [23]), experiments performed in Refs. [24] and [25] were successful in using an inner loop reference governor to enforce compressor surge constraints in turbocharged gasoline engines.

Due to the aforementioned limitations arising from uncertain future lead vehicle velocity, the CG strategy in our work uses a truncated analogy of the maximal output admissible set, denoted as OT, where OT is the set of all originating states, x(t), and inputs, uCG, such that if the input is held constant over some finite prediction horizon, constraints are satisfied (also referred to as the i-step output admissible set in Ref. [26]). The finite horizon is chosen to reasonably reflect the future horizon over which the lead vehicle's velocity profile can be predicted. In the block diagram of Fig. 2, the CG lies directly downstream of the MPC, receiving a prescribed wheel force, uMPC, as an input and outputting an adjusted wheel force uCG, whenever not adjusting uMPC would result in constraint violation. The term uCG is the input to the lower level powertrain controller. The CG strategy is formulated as follows:

(19a)
(19b)

The CG adjusts uCG(t) only when it is necessary to satisfy constraints. If no constraint violation occurs over the CG horizon, uCG(t)=uMPC(t). If a constraint violation occurs over the CG horizon, the minimization in Eq. (19) is performed via bisection search. The maximum correction the CG can apply is uCG=umax,brk, where umax,brk is the maximum negative force that can be applied to the road through the wheel via braking.

The CG is formulated to enforce two minimum following distance constraints:

  1. A desired minimum following distance, slarge, at the end of the CG horizon, Tlarge.

  2. A minimum safe following distance, ssmall, that must be enforced at every time step along some beginning portion of the CG horizon.

The reason for the incorporation of two following distance constraints in the CG formulation is driven by the fact that the lead vehicle's velocity profile will often differ from what the CG assumes. Specifically, while the actual velocity profile of the lead vehicle is unknown, its velocity is assumed by the CG to be constant over the prediction horizon. If only the minimum following distance, ssmall, were enforced over the prediction horizon, then the CG would allow the ego vehicle to travel at a following distance near that minimum, under the assumption of a constant-speed lead vehicle. If the lead vehicle slowed down unexpectedly instead of remaining at the assumed constant speed, then the CG would have no choice but to apply a large braking force at the subsequent time-step. To mitigate this issue, our proposed algorithm introduces an additional terminal constraint at time Tlarge, which requires a deceleration profile that forces the ego vehicle ultimately to back off to a larger following distance, slarge. As illustrated in Fig. 3, this results in a buffer between the ego vehicle's actual following distance, s(t), and the absolute minimum allowable following distance (ssmall), thereby avoiding large braking events upon every unexpected deceleration of the lead vehicle.

Based on the constraints of Fig. 3, the truncated output admissible set, OT, is defined as follows:

Definition 1. Definition (Truncated Output Admissible Set): OT is the set of all initial state/control pairs,(x(t),uCG)such that ifuCG(t¯)=uCG,t¯[tt+Tlarge], then:

  • s(t+Tlarge|t)slarge,

  • s(t̃|t)ssmall, t̃[tt+Tsmall].

The prediction horizon, Tlarge, is discretized into Nlarge time steps, each having length ΔtCG. The CG adjustment in Eq. (19) is performed at every time-step, ΔtCG. Whenever the current state, x(t), and current MPC output, uMPC(t), are elements of the set OT, (i.e., uMPC satisfies constraints), uCG=uMPC. Otherwise, a bisection search, detailed in Algorithm 1, is used by the command governor to find the smallest adjustment required to satisfy the constraints specified in the definition of OT. In Algorithm 1, ϵ is the convergence tolerance. The smaller receding horizon, Tsmall, is discretized into Nsmall steps, each also having length ΔtCG. Values for the parameters used in the CG formulation are given in Sec. 4.1.

4 Results

Simulations of the cascaded MPC and CG-based Eco-ACC strategy were performed on a heavy-duty truck over a highway route for various CG horizon lengths, Tlarge. In this section, we present these results and assess the impact of CG parameters on fuel economy and drivability.

4.1 Simulation Parameters.

Distance and elevation data for three representative trucking routes furnished by Volvo Group North America, denoted by HWY-1, HWY-2, and HWY-3, with lengths of 180 km, 360 km, and 240 km, respectively, were used in simulations. Additionally, simulations were performed for a fully loaded and a half-loaded trailer, resulting in total truck weights of 35,000 kg and 20,000 kg, respectively. A stochastic lead vehicle traffic model, developed and calibrated using highway traffic data in Ref. [13], was used to provide multiple lead vehicle velocity profiles over the entire route. Over the representative trucking routes HWY-1, HWY-2, and HWY-3, a total of 29, 32, and 40 lead vehicles were encountered, respectively. For the baseline strategy, a Gipps' car-following model was used to determine the velocity setpoint, where the desired following distance was set to slarge. In all the simulations performed, tlarge=3 s and tsmall=1 s, where slarge=tlargevlead and ssmall=tsmallvlead. The time-step of the CG, ΔtCG, was set to 200 ms for all simulations. Tsmall was held at a relatively short time horizon of 2 s to prevent unnecessary adjustments of applied wheel force, as the approximation of the lead vehicle's future behavior had less accuracy at longer horizons. The MPC used a horizon length of 2000 m and a step size, ΔxMPC, of 40 m. Weight λb in Eq. (18) was set 100 to place a greater penalty on the energy loss due to braking than the mechanical energy expended, as it was shown in Ref. [11] that the majority of fuel savings realized by ecological driving stem from avoiding unnecessary braking events. Weight λd in Eq. (18) was tuned heuristically via preliminary highway driving simulations for the Eco-ACC presented in this work where Tlarge was set to 30 s. Based on the preliminary highway driving simulation results shown in Fig. 4, λd was set to 0.1 in order to achieve the most fuel savings without compromising trip time. The MPC optimization was implemented every 1 s, around every 20–30 m at the simulated highway speeds.

4.2 Performance.

In assessing the ecological performance of the proposed Eco-ACC strategy, the energy expended, and sources thereof, were analyzed along with fuel consumption. Fuel consumption data were calculated within the proprietary heavy-duty truck model. The total mechanical energy expended, Emechtot, was calculated postsimulation as
(20)

where uwh is the realized propulsive force applied through the wheel to the road. Two critical components of total energy expenditure are:

  • The total energy dissipated by braking, Ebraketot.

  • The total energy lost due to aerodynamic drag, Eaerotot.

Ebraketot and Eaerotot were calculated postsimulation as
(21)
(22)

Ecological performance and drivability are reported in Figs. 5 and 6 for a fully loaded and half-loaded trailer, respectively. Figures 5(a) and 6(a) show the total energy expended and fuel consumed for various values of Tlarge. Fuel economy improves as Tlarge increases, and then plateaus for Tlarge25s. In Figs. 5(b) and 6(b), the energy savings due to the reduction of braking and aerodynamic drag are compared to the baseline. The energy expended due to aerodynamic drag is largely dependent on trip time. As a result, negative energy savings due to drag indicate that the Eco-ACC strategy completed the trip faster than the baseline. The results in Figs. 5(b) and 6(b) indicate that a reduction in braking was responsible for the vast majority of total energy savings.

Drivability was assessed via the mean squared jerk, denoted as MSJ, of the vehicle in simulation over the entire route. MSJ was calculated as
(23)

where jego is the jerk of the ego vehicle and Ttrip is the total trip time. Drivability results in Figs. 5(c) and 6(c) indicate comparable drivability to the baseline strategy. The best drivability results occurred when 10sTlarge30s. In Sec. 4.3, we analyze how Tlarge affected vehicle-following behavior and how these behaviors impacted performance.

4.3 Vehicle-Following Behavior.

In order to gain an understanding of how the Eco-ACC strategy modulates the velocity and following distance of the ego vehicle under various CG horizon lengths, Tlarge, a stretch of simulated highway driving where the heavy-duty truck engaged in vehicle-following is examined. The vehicle-following scenario in Fig. 7 occurred on HWY-3 for a fully loaded trailer, during which a lead vehicle entered and exited the lane at around 146 km and 151 km, respectively. The lead vehicle entered the lane at an initial following distance near ssmall, traveling around 1 m s−1 slower than the Eco-ACC strategy. Consequently, upon the lead vehicle entering the lane, every Eco-ACC simulation applied a braking force.

Before the lead vehicle entered the lane, the Eco-ACC maintained a velocity near the offline optimized velocity trajectory, vDP*, which is expected due to the penalty term in Eq. (18). When the lead vehicle entered the lane, the CG began modulating the prescribed wheel torque by the MPC to enforce the predicted vehicle-following constraints. Additionally, the desired velocity, vDP*, for this vehicle-following scenario was greater than the lead vehicle's velocity. Consequently, the realized velocity of the Eco-ACC simulations deviated from vDP* while the lead vehicle was present. However, the MPC was still able to engage in ecological driving whenever the prescribed MPC wheel torque satisfied the vehicle-following constraints enforced by the CG. For instance, as the Eco-ACC simulations climbed a relatively steep hill, near 150 km, the MPC prescribed a reduced velocity for the truck, and the Eco-ACC simulations began to follow a similar velocity trend as the offline optimized velocity trajectory. After the lead vehicle exited the lane, the Eco-ACC maintained a slower velocity than the offline optimized solution, but followed a similar velocity trend, until utilizing a downhill portion of the route, starting at 152 km, to accelerate back to a velocity near vDP*.

To investigate reasons for the plateau in ecological performance for Tlarge25s, the cumulative energy loss due to braking is shown in Fig. 7(b). The greatest energy losses due to braking occurred when the lead vehicle entered the lane. Eco-ACC simulations with smaller Tlarge values expended more braking energy upon the initial entry of the lead vehicle, specifically when Tlarge<20s, due to applying a larger braking effort to quickly achieve sslarge. However, Eco-ACC simulations where Tlarge was longer had the tendency to stay near ssmall after the lead vehicle entered the lane. This required the CG to apply a large braking effort if the lead vehicle suddenly slowed down, an example instance of which is seen for Tlarge=150s around 147.5 km in Fig. 7.

Drivability for the vehicle-following scenario of Fig. 7 was evaluated using the cumulative sum of the vehicle jerk squared, shown in Fig. 7(d). Drivability was affected by Tlarge similarly to the way ecological performance was affected by Tlarge. The large braking events that occurred for Tlarge<20s and Tlarge>52s had a negative effect on drivability.

5 Conclusion

This paper presented algorithmic details and simulation results for an Eco-ACC strategy that combines MPC for ecological driving with a command governor for safe vehicle following. An analysis on the effect controller parameters have on performance, in terms of both efficiency and drivability, was performed. Results from our analysis demonstrated a consistent reduction in fuel consumption when the CG horizon was increased up to a point. Simulations performed with a longer Tlarge had the tendency to result in a following distance that approached ssmall more often. In these cases, any small braking action on the part of the lead vehicle resulted in a sudden corrective ego vehicle braking effort that had a negative effect on fuel economy and drivability. Specifically, for the heavy-duty truck considered in this work, the best ecological performance was realized for 20sTlarge40s.

Acknowledgment

This research was funded by the Advanced Research Projects Agency-Energy (ARPA-E), U.S. Department of Energy, under Award No. DE-AR-0000801. The authors would also like to acknowledge Volvo Group North America for their assistance and support.

Funding Data

  • Advanced Research Projects Agency–Energy (Funder ID: 10.13039/100006133).

References

1.
U.S. Environmental Protection Agency
,
2016
, “
Inventory of U.S. Greenhouse Gas Emissions and Sinks: 1990–2014
,” EPA, Washington, DC, Report No. EPA 430-R-16-002.
2.
U.S. Environmental Protection Agency
,
2016
, “
Greenhouse Gas Emissions and Fuel Efficiency Standards for Medium and Heavy-Duty Engines and Vehicles—Phase 2
,” EPA, Washington, DC, Report No. EPA-HQ-OAR-2014-0827.
3.
U.S. Department of Transportation
,
2017
, “
Freight Facts and Figures: 2017
,” USDOT, Washington, DC, Report No. DOT:34923.
4.
Sciarretta
,
A.
,
Nunzio
,
G. D.
, and
Ojeda
,
L. L.
,
2015
, “
Optimal Ecodriving Control: Energy-Efficient Driving of Road Vehicles as an Optimal Control Problem
,”
IEEE Control Syst. Mag.
,
35
(
5
), pp.
71
90
.10.1109/MCS.2015.2449688
5.
Kamal
,
M. A. S.
,
Mukai
,
M.
,
Murata
,
J.
, and
Kawabe
,
T.
,
2011
, “
Ecological Vehicle Control on Roads With Up-Down Slopes
,”
IEEE Trans. Intell. Transp. Syst.
,
12
(
3
), pp.
783
794
.10.1109/TITS.2011.2112648
6.
Wang
,
M.
,
Daamen
,
W.
,
Hoogendoorn
,
S. P.
, and
van Arem
,
B.
,
2012
, “
Driver Assistance Systems Modeling by Model Predictive Control
,”
15th International IEEE Conference on Intelligent Transportation Systems
, Anchorage, AK, Sept. 16–19, pp.
1543
1548
.10.1109/ITSC.2012.6338824
7.
Li
,
S. E.
,
Li
,
K.
, and
Wang
,
J.
,
2013
, “
Economy-Oriented Vehicle Adaptive Cruise Control With Coordinating Multiple Objectives Function
,”
Veh. Syst. Dyn.
,
51
(
1
), pp.
1
17
.10.1080/00423114.2012.708421
8.
Li
,
S. E.
,
Jia
,
Z.
,
Li
,
K.
, and
Cheng
,
B.
,
2015
, “
Fast Online Computation of a Model Predictive Controller and Its Application to Fuel Economy-Oriented Adaptive Cruise Control
,”
IEEE Trans. Intell. Transp. Syst.
,
16
(
3
), pp.
1199
1209
.10.1109/TITS.2014.2354052
9.
Hellström
,
E.
,
Fröberg
,
A.
, and
Nielsen
,
L.
,
2006
, “
A Real-Time Fuel-Optimal Cruise Controller for Heavy Trucks Using Road Topography Information
,”
SAE
Paper No. 2006-01-0008.10.4271/2006-01-0008
10.
Henzler
,
M.
,
Buchholz
,
M.
, and
Dietmayer
,
K.
,
2014
, “
Online Velocity Trajectory Planning for Manual Energy Efficient Driving of Heavy Duty Vehicles Using Model Predictive Control
,” 17th International IEEE Conference on Intelligent Transportation Systems (
ITSC
), Quingdao, China, Oct. 8–11, pp.
1814
1819
.10.1109/ITSC.2014.6957956
11.
Groelke
,
B.
,
Borek
,
J.
,
Earnhardt
,
C.
,
Li
,
J.
,
Geyer
,
S.
, and
Vermillion
,
C.
,
2018
, “
A Comparative Assessment of Economic Model Predictive Control Strategies for Fuel Economy Optimization of Heavy-Duty Trucks
,” Annual American Control Conference (
ACC
), Milwaukee, WI, June 27–29, pp.
834
839
.10.23919/ACC.2018.8431050
12.
Earnhardt
,
C.
,
Groelke
,
B.
,
Borek
,
J.
,
Naghnaeian
,
M.
, and
Vermillion
,
C.
,
2021
, “
A Multirate, Multiscale Economic Model Predictive Control Approach for Velocity Trajectory Optimization of a Heavy Duty Truck
,”
ASME J. Dyn. Syst. Meas. Control
,
143
(
3
), p.
031006
.10.1115/1.4048658
13.
Borek
,
J.
,
Groelke
,
B.
,
Earnhardt
,
C.
, and
Vermillion
,
C.
,
2020
, “
Economic Optimal Control for Minimizing Fuel Consumption of Heavy-Duty Trucks in a Highway Environment
,”
IEEE Trans. Control Syst. Technol.
,
28
(
5
), pp.
1652
1664
.10.1109/TCST.2019.2918472
14.
Borek
,
J.
,
Groelke
,
B.
,
Earnhardt
,
C.
, and
Vermillion
,
C.
,
2019
, “
Optimal Control of Heavy-Duty Trucks in Urban Environments Through Fused Model Predictive Control and Adaptive Cruise Control
,” American Control Conference (
ACC
), Philadelphia, PA, July 10–12, pp.
4602
4607
.10.23919/ACC.2019.8814703
15.
Corona
,
D.
, and
Schutter
,
B. D.
,
2008
, “
Adaptive Cruise Control for a Smart Car: A Comparison Benchmark for MPC-PWA Control Methods
,”
IEEE Trans. Control Syst. Technol.
,
16
(
2
), pp.
365
372
.10.1109/TCST.2007.908212
16.
Soroa
,
I. M.
,
Ibrahim
,
A.
,
Goswami
,
D.
, and
Li
,
H.
,
2019
, “
Feasibility Study and Benchmarking of Embedded MPC for Vehicle Platoons
,”
Workshop on Autonomous Systems Design (ASD 2019)
, OpenAccess Series in Informatics (OASIcs), Vol.
68
,
S.
Saidi
,
R.
Ernst
, and
D.
Ziegenbein
, eds., Schloss Dagstuhl–Leibniz-Zentrum fuer Informatik, Florence, Italy, pp.
2:1
2:15
.
17.
Kolmanovsky
,
I.
,
Garone
,
E.
, and
Cairano
,
S. D.
,
2014
, “
Reference and Command Governors: A Tutorial on Their Theory and Automotive Applications
,”
American Control Conference
, Portland, OR, June 4–6, pp.
226
241
.10.1109/ACC.2014.6859176
18.
Casavola
,
A.
,
Mosca
,
E.
, and
Angeli
,
D.
,
2000
, “
Robust Command Governors for Constrained Linear Systems
,”
IEEE Trans. Autom. Control
,
45
(
11
), pp.
2071
2077
.10.1109/9.887628
19.
Groelke
,
B.
,
Earnhardt
,
C.
,
Borek
,
J.
, and
Vermillion
,
C.
,
2018
, “
A Cascaded Multi-Rate Model Predictive Control and Reference Governor Approach for Real-Time Velocity Optimization in the Presence of Traffic
,”
14th International Symposium on Advanced Vehicle Control
, Beijing, China, June 20–23.
20.
Osorio
,
J.
,
Santillo
,
M.
,
Seeds
,
J. B.
,
Jankovic
,
M.
, and
Ossareh
,
H. R.
,
2019
, “
A Reference Governor Approach Towards Recovery From Constraint Violation
,” American Control Conference (
ACC
), Philadelphia, PA, July 10–12, pp.
1779
1785
.10.23919/ACC.2019.8815337
21.
Garone
,
E.
,
Cairano
,
S. D.
, and
Kolmanovsky
,
I.
,
2017
, “
Reference and Command Governors for Systems With Constraints: A Survey on Theory and Applications
,”
Automatica
,
75
, pp.
306
328
.10.1016/j.automatica.2016.08.013
22.
Kalabić
,
U.
, and
Kolmanovsky
,
I.
,
2015
, “
Inner-Loop Reference Governors: Placing Reference Governors Inside the Control Loop by Using Passivity
,” 54th IEEE Conference on Decision and Control (
CDC
), Osaka, Japan, Dec. 15–18, pp.
3019
3025
.10.1109/CDC.2015.7402592
23.
Kalabić
,
U.
, and
Di Cairano
,
S.
,
2018
, “
Inner-Loop Reference Governor Design With an Application to Human-in-the-Loop Control
,” European Control Conference (
ECC
), Limassol, Cyprus, June 12–15, pp.
1021
1026
.10.23919/ECC.2018.8550423
24.
Kalabić
,
U.
,
Kolmanovsky
,
I.
,
Buckland
,
J.
, and
Gilbert
,
E.
,
2011
, “
Reference and Extended Command Governors for Control of Turbocharged Gasoline Engines Based on Linear Models
,” IEEE International Conference on Control Applications (
CCA
), Denver, CO, Sept. 28–30, pp.
319
325
.10.1109/CCA.2011.6044457
25.
Kalabić
,
U. V.
,
Buckland
,
J. H.
,
Cooper
,
S. L.
,
Wait
,
S. K.
, and
Kolmanovsky
,
I. V.
,
2016
, “
Reference Governors for Enforcing Compressor Surge Constraints
,”
IEEE Trans. Control Syst. Technol.
,
24
(
5
), pp.
1729
1739
.10.1109/TCST.2015.2510334
26.
Hatanaka
,
T.
, and
Takaba
,
K.
,
2008
, “
Probabilistic Assurance of Constraint Fulfillment Against Model Uncertainties and Disturbances
,”
IFAC Proc. Vol.
,
41
(
2
), pp.
1147
1152
.10.3182/20080706-5-KR-1001.00198