Download as pdf or txt
Download as pdf or txt
You are on page 1of 16

JOURNAL OF GUIDANCE, CONTROL, AND DYNAMICS

Vol. 40, No. 2, February 2017

Customized Real-Time Interior-Point Methods


for Onboard Powered-Descent Guidance

Daniel Dueri∗ and Behçet Açıkmeşe†


University of Washington, Seattle, WA
Daniel P. Scharf‡
Jet Propulsion Laboratory, California Institute of Technology, Pasadena, California 91109
and
Matthew W. Harris§
The University of Texas at Austin, Austin, Texas 78712
DOI: 10.2514/1.G001480
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

This paper presents a new onboard-implementable, real-time convex optimization-based powered-descent


guidance algorithm for planetary pinpoint landing. Earlier work provided the theoretical basis of convexification,
the equivalent representation of the fuel-optimal pinpoint landing trajectory optimization problem with nonconvex
control constraints as a convex optimization problem. Once the trajectory optimization problem is convexified, interior-
point method algorithms can be used to solve the problem to global optimality. Though having this guarantee
of convergence motivated earlier convexification results, there were no real-time interior point method algorithms
available for the computation of optimal trajectories on flight computers. This paper presents the first such algorithm
developed for onboard use and flight-tested on a terrestrial rocket with the NASA Jet Propulsion Laboratory and
the NASA Flight Opportunities Program in 2013. First, earlier convexification results are summarized and the
resulting second-order cone-programming problem for fuel-optimal trajectory optimization is presented. Then, the
proposed, fairly generic, second-order cone-programming interior point method algorithm is presented in detail with an
overview of the customization process for real-time computations. Customization exploits a specific problem structure to
increase the computational speed, which is shown to decrease run times by two to three orders of magnitude in many
applications. A new convexification result for maximal-divert trajectories with active velocity constraints is also
presented herein.

I. Introduction PDG is obtained via lossless convexification, which is the conversion


of nonconvex optimization problems with specific structure into
T HE recent successes of the Mars Science Laboratory (MSL)
have rekindled interest for planetary powered-descent guidance
(PDG). Powered descent is a phase of planetary landing that takes a
convex ones [8–10,17–19]. Once convexified, interior point methods
(IPMs) can be used to find the global optimum with polynomial-time
vehicle from kilometers above the surface to near-zero speed near the complexity, guaranteed convergence for feasible problems, and
surface [1–3]. Earlier research [4,5] showed that the ability to without the need for an initial feasible trajectory to seed the optimi-
generate optimal PDG trajectories onboard and in real time can zation [20–22]. All of these characteristics are ideal for onboard
significantly enhance a vehicle’s landing accuracy, thus allowing for implementation.
pinpoint landings (landings within several hundred meters of a target) Thus, an onboard IPM solver is needed that can find solutions to
[6]. Such improvements in landing accuracy can enable a new class of the PDG optimal control problem in real-time. This paper first
exciting missions to currently inaccessible landing sites, such as presents an effective IPM algorithm that has undergone nearly a
valleys and craters on Mars. PDG is fundamentally a constrained [7] decade of verification and a customization methodology [23–25] that
optimal control problem [8–11], and the goal is to quickly and improves runtimes for onboard implementation. Although other
reliably solve this problem onboard a lander. general IPM solvers are developed in the literature, the one in this
Several computationally efficient, suboptimal algorithms have paper is presented because of its rich verification history and because
been developed for PDG [12–16]. However, explicitly considering it forms the basis of the real-time custom IPM solver that has been
mission and vehicle constraints is critical for long diverts; otherwise, flight tested. Custom IPM solvers take full advantage of a specific
approximate methods can produce trajectories that vehicles cannot problem structure to significantly reduce the number of mathematical
track or that are unsafe to track (e.g., by throttling below a minimum operations and computational branches used by the solver’s
safe threshold or requiring subsurface flight) [8–10]. An optimal executable [23,24,26,27]. The latter point is critical for the verifi-
control methodology that includes all of the relevant constraints for cation of flight software, as each branch must be verified to ensure
that no corner cases can stall execution. Note that the customization
process described here can be applied to other IPM algorithms. The
Received 16 May 2015; revision received 20 January 2016; accepted for convexified PDG problem has been successfully and repeatedly
publication 13 May 2016; published online 10 October 2016. Copyright ©
2016 by Behçet Açıkmeşe. Published by the American Institute of
flight tested on a terrestrial vertical takeoff and landing rocket [28–
Aeronautics and Astronautics, Inc., with permission. Copies of this paper may 30] using a customized IPM solver, with test flight data and
be made for personal and internal use, on condition that the copier pay the per- verification methods presented in a companion paper [31].
copy fee to the Copyright Clearance Center (CCC). All requests for copying In addition, earlier convexification results [8–10,19,32] do not ensure
and permission to reprint should be submitted to CCC at www.copyright.com; that the convexification is lossless for trajectories with simultaneously
employ the ISSN 0731-5090 (print) or 1533-3884 (online) to initiate your active thrust-pointing [9] and velocity upper-bound constraints. Active
request. state constraints, such as velocity bounds, complicate the form of
*daniel.dueri@utexas.edu. Student Member AIAA.
† Pontryagin’s maximum principle [33–35] used in proofs, thus making it
behcet@austin.utexas.edu. Associate Fellow AIAA.

Senior Engineer, Guidance and Control Analysis Group, 4800 Oak Grover difficult to establish a very general convexification theory with active
Dr., M/S 198-326; Daniel.P.Scharf@jpl.nasa.gov. Senior Member AIAA. state constraints. In [8,10], the first lossless convexification results are
§
Department of Aerospace Engineering and Engineering Mechanics, 1 established without incorporating thrust-pointing constraints. These
University Station, C0600; m_harris@utexas.edu. Student Member AIAA. results are generalized to the case with thrust-pointing constraints in [9].
197
198 DUERI ET AL.

In these results, the convexification is shown to be lossless for optimal R represents the vehicle’s mass, T ∈ R3 is the thrust force, g ∈ R3
trajectories without active state constraints or with momentarily active corresponds to gravitational acceleration, α ∈ R is a positive
state constraints (on a finite number of time instances). In [19], these constant that describes the mass flow rate, ω ∈ R3 is the planet’s
results are extended to optimal trajectories with active velocity rotational rate vector, and Sω ∈3×3 is a skew symmetric matrix
constraints on finite time intervals. Finally, the theory is extended to describing the cross-product operation [8]. The components of r are
allow for continuously active polytopic state constraints in [32]. defined as follows: r1 corresponds to the downrange, r2 corresponds to
Therefore, the second contribution of this paper is to present an crossrange, and r3 is the altitude. All of the initial conditions for the
extension of lossless convexification for trajectories with simulta- system are specified and denoted with a subscript zero. The vehicle is
neously active velocity-bound constraints and thrust-pointing required to land softly on the surface; thus, the final positions and
constraints. This extension is important because the results for the test velocities are specified (without loss of generality) and are denoted
flights in 2013 [29,36] make use of trajectories that are simultaneously with a subscript f:
limited by speed and thrust direction. More specifically, the test rocket
was at its maximum velocity for more than 75% of its descent [31]. rt0   r0 ; vt0   v0 ; mt0   m0 ;
Thus, the theory presented herein is necessary to guarantee that the r3 tf   0; vtf   0 (2)
optimal solutions to the convexified PDG problem demonstrated in the
test flights are also optimal for the original PDG problem. Thus, the final range, crossrange, and mass are free; however, the
Finally, it is not sufficient for the PDG algorithm to be fast on a final mass cannot be less than the dry mass md , of the vehicle; that is,
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

modern desktop processor. The PDG problem must be rapidly solved mtf  ≥ md . There are a number of additional constraints that any
on a radiation-hardened flight processor. Such “rad-hard” processors feasible trajectory must satisfy. A velocity upper-bound constraint
are significantly slower and have architectural differences that make keeps the vehicle’s thrusters operating in a safe (subsonic) regime.
them more robust to radiation-induced damage. For example, a state- Given a velocity upper bound V c , the speed constraint is given by
of-the-art flight processor has a clock speed of 200 MHz, an order of
magnitude slower than the average desktop processor. As a result, the kvtk ≤ V c (3)
runtimes of the customized PDG algorithm are characterized on a
BAE RAD750 flight processor. Runtimes on the order of 0.7 s are Second, the glideslope constraint keeps the vehicle in an inverted cone
achieved, indicating the appropriateness of the PDG algorithm for with its tip at the landing point [9,10]:
onboard implementation on rad-hard processors.
The paper is organized as follows: Sec. II gives a summary of the tan γkr1 t; r2 tk ≤ r3 t (4)
PDG problem formulation; Sec. III describes the real-time IPM
algorithm used; Sec. IV describes the automated solver generation for in which γ ∈ 0; 90 deg is the minimum admissible glideslope angle.
real-time implementation; Sec. V established the proof of lossless The control constraints define the feasible thrust regime via an
convexification with active velocity and thrust-pointing constraints; upper and a lower bound. A lower bound is needed because engines
Sec. VI presents simulated numerical results; Sec. VI.C presents typically cannot operate reliably below a certain throttle level. The
experimental solver timing results on flight-like processors; and upper bound exists because arbitrarily large thrusts are impossible.
Sec. VII summarizes the conclusions of this research.
0 < ρ1 ≤ kTtk ≤ ρ2 (5)
II. Fuel-Optimal PDG for Planetary Pinpoint Landing
This constraint is not convex due to the lower-bound
This section summarizes the formulation of the optimal control constraint (Fig. 1).
problem for fuel-optimal PDG along with earlier convexification Finally, we consider the thrust-pointing constraint given by
results [8–10,19]. The section concludes with the discretization of the
convex optimal control problem, which produces a finite- n^ T Tt ≥ kTtk cos θ (6)
dimensional second-order cone-programming (SOCP) problem
[21]. This material is needed for the extended convexification results in which n^ ∈ R3 is a unit vector describing a desired pointing
with active constraints. direction and θ ∈ 0; π is a specified angle that represents the size of
the feasible thrust-pointing arc about n. ^ This constraint is convex
A. Review of the Fuel-Optimal PDG Problem Formulation when θ ≤ π∕2 and nonconvex when θ > π∕2. The unit vector and
The PDG problem is a finite-time-horizon optimal control problem angle define a cone in which the thrust vector must reside. Such a
where fuel-optimal trajectories are sought that satisfy the relevant constraint arises due to sensors (such as a camera) that must keep the
state and control constraints imposed by the vehicle capabilities and ground in its field of view.
mission requirements. We assume that 1) the only forces acting on the Obtaining a fuel-optimal trajectory for the PDG problem is
vehicle are due to the control thrust and gravity (i.e., there are equivalent to maximizing the mass of the vehicle at landing.
negligible aerodynamic forces, which is particularly true on Mars due Therefore, the fuel-optimal PDG problem is given by Problem 1
to its low atmospheric density); 2) the vehicle is sufficiently close to Problem 1: Nonconvex Fuel-Optimal PDG Problem
the surface to warrant a flat planet model, in which the acceleration
due to gravity is constant; and 3) the vehicle’s attitude control is of maximize: J  mtf 
sufficiently high bandwidth that the translational and rotational
dynamics can be decoupled. As a consequence of the last assumption, subject to: rt
_  vt; rt0   r0 ; r3 tf   0
we do not include the attitude dynamics in the formulation, and Tt
assume that any lander orientation needed to obtain the desired thrust vt
_  − Sω2 rt − 2Sωvt − g;
mt
vector can be obtained instantaneously. The translational equations
of motion under these assumptions are vt0   v0 ; vtf   0
_  −αkTtk;
mt mt0   m0 ; md ≤ mtf 
rt
_  vt;
0 < ρ1 ≤ kTtk ≤ ρ2 ; n^ T Tt ≥ kTtk cos θ
Tt
vt
_  − Sω2 r − 2Sωv − g; kvtk ≤ V c ; tan γkr1 t; r2 tk ≤ r3 t
mt
_
mt  −αkTtk (1)
B. Lossless Convexification of the Fuel-Optimal PDG Problem
in which r ∈ R3 is the position of the vehicle relative to some planet- As stated, Problem 1 is highly constrained and nonconvex. There
fixed coordinate frame, v ∈ R3 is the corresponding velocity, m ∈ are three sources of nonconvexity in the formulation: 1) the lower
DUERI ET AL. 199

Fig. 1 Feasible set of controls with pointing constraints and upper/lower norm bounds for a two-dimensional control vector.

bound on the thrust magnitude, 2) the nonlinear dynamics caused by _


mt
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

the interaction between thrust and mass, and 3) the thrust-pointing z_t   −ασt
mt
constraint (if θ > π∕2). In general, such problems do not have closed-
form solutions and must be solved numerically. Because convex which results in a linear equality constraint. Up to this point, all
problems can be solved to global optimality using polynomial-time operations have resulted in lossless convexifications. However, the
IPM algorithms, converting the problem to a convex form offers upper- and lower-bound constraints on Γ in Eq. (5) become
significant computational advantages, which motivate the following nonconvex due to this choice of variables. Thus, a Taylor series
discussion on the convexification of the problem. approximation is applied to convexify these constraints. The
First, consider the nonconvex control domain. Applying the resulting convex control constraints in the transformed variables are
convexification in [8,10], the convexified PDG problem is presented
9
in Problem 2, in which Γ ∈ R is a new slack variable that relaxes the kutk ≤ σt; n^ T ut ≥ σt cos θ =
control constraints by lifting the control space. −z
ρ1 e 0 1 − zt − z0 t ≤ σt ∀ t ∈ 0; tf 
Problem 2: Fuel-Optimal PDG Problem with Lossless Convexi- ;
σt ≤ ρ2 e−z0 1 − zt − z0 t
fication of the Control Constraints
in which z0 t  lnm0 − αρ2 t. An analysis of the error incurred
maximize: J  mtf  through this approximation can be found in [31]. Combining all of the
subject to: rt
_  vt; rt0   r0 ; r3 tf   0 convexifications introduced, the fuel-optimal PDG problem becomes
the following convex optimization problem:
Tt Problem 3: Convexified Fuel-Optimal PDG Problem
vt
_  − Sω2 rt − 2Sωvt − g;
mt
vt0   v0 ; vtf   0 maximize: J ztf 

_  −αΓt;
mt mt0   m0 ; md ≤ mtf  subject to: r_tvt; rt0 r0 ; r3 tf 0

n Tt ≥ Γ cos θ;
^T kTtk ≤ Γt; 0 < ρ1 ≤ Γt ≤ ρ2 vtut−Sω
_ 2 rt−2Sωvt−g;

kvtk ≤ V c ; tan γkr1 t;r2 tk ≤ r3 t vt0  v0 ; vtf 0


z_t−ασt; zt0 lnm0 ; lnmd ≤ztf ;
The objective of lossless convexification of the control constraints is
n^ T ut≥σ cos θ; kutk≤σt;
to establish that solutions to the relaxed optimal control problem in
Problem 2 are also solutions to the original formulation in Problem 1; ρ1 e−z0 t 1−zt−z0 t≤σt≤ρ2 e−z0 t 1−zt−z0 t
in other words, the control relaxation in Problem 2 has no impact on
kvtk≤V c ; tan γkr1 t;r2 tk≤r3 t
the optimal solutions. Section V focuses on showing that this control
relaxation remains lossless for simultaneously active maximum
speed and thrust-pointing constraints for trajectories that are repre- Note that Problem 3, which is an optimal control problem, is solvable
sentative of the Masten test flights. by convex programming methods after a discretization to convert it
into a parameter optimization problem.
C. Time-Varying Mass
D. Canonicalization of the PDG Problem
Two nonconvexities remain in the formulation of Problem 2: 1) the
nonlinear interaction between thrust and mass in the dynamics and In this section, Problem 3 is transformed into the standard form of
2) the nonconvex thrust-pointing constraint when θ ≥ π∕2. While the an SOCP [21,22], which is required to obtain a solution via IPMs.
nonlinear mass dynamics are not problematic for the proof in Sec. V, Problem 3 is first discretized to convert it into a finite-dimensional
the dynamics must still be convexified to compute solutions by using convex parameter optimization problem. The process involves a time
convex programming methods. First, a change of variables is per- discretization of the thrust (control) vector [8,10]. Note that,
formed, and then the control constraints are approximated with a regardless of the type of time discretization employed, the resulting
Taylor series. A very brief overview of this procedure is given here to system will have linear discrete-time dynamics with linear inequality
present a purely convex trajectory optimization problem, with details and convex quadratic inequality constraints.
given in Sec. III.B of [8]. First, let Let the state vector, ξt ∈ R7 , be
" #
zt
Γt Tt
σt ≜ ; ut ≜ ; zt ≜ ln mt ξt  rt
mt mt vt

Then, the mass dynamics become Then, the discretized dynamics in Problem 3 can be expressed as
200 DUERI ET AL.

ξk1  Fξk  Guk ; k  1; : : : ; p − 1 III. A Real-Time IPM Algorithm to Solve SOCP


Problems
in which F ∈ R7×7 and G ∈ R7×3 and their explicit construction is This section reviews an IPM algorithm for SOCPs and introduces the
quite straight forward and can be found in [8]. Thus, the dynamics notation necessary to describe the contributions detailed in Sec. IV [24].
form a series of p − 1 linear equality constraints. Next, the feasible The IPM algorithm described here has successfully solved millions of
domains of the p − 1 unknown states and p − 1 unknown controls PDG problems over the last nine years (since 2007 [8]) as part of
are expressed via two types of convex cones: the positive (or linear) extensive Monte Carlo studies for Mars landings [6]. These numerical
cone K and the second-order cone Ks [21,22,24]. All of the solution results supplemented the theoretical convergence guarantees [20,22]
variables involved are constrained to be in one of these two types of with empirical evidence for its robustness and effectiveness. Although
cones, sometimes by introducing slack variables. there are a variety of IPM algorithms in the literature, the one presented
Definition 1: A positive cone, KnL ⊂ Rn , is a convex set defined by here has been developed for the relevant aerospace application of
planetary PDG, has been rigorously tested over the span of almost a
KnL  fw ∈ Rn ∶w ≥ 0g ⊆ Rn decade, and has been demonstrated on terrestrial test flights. Thus, the
IPM in this section has a very rich aerospace verification history that sets
in which the ≥ operator refers to an elementwise inequality. The it apart from other solvers; especially because the verification effort for
positive cone is used to describe all variables that are either aerospace applications is very demanding due to severe safety and cost
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

unconstrained or linearly constrained and that are not quadratically concerns. Finally, numerous algorithmic choices must be made while
constrained. For example, if the variable w is unconstrained, it is implementing an IPM. As demonstrated via Monte Carlo simulations
replaced by two variables in the positive cone, w  w − w− in and flight tests [6,29], the algorithmic choices documented here are
which w ≥ 0 and w− ≥ 0. If the variable is linearly constrained (i. effective and robust. Hence, we believe that presenting the details of this
e., hT w ≤ d), then we let w  w − w− as before; and, rigorously verified algorithm can prove useful for engineers to
implement IPMs for many control system applications in aerospace
hT w − w−   ws  d; where w ≥ 0; w− ≥ 0; ws ≥ 0 (e.g., [11,37,38]) and other fields.
Generally, the objective of an SOCP solver is to find an optimal
solution of the primal problem, given (in canonical form) by Eq. (8).
Definition 2: A second-order cone (SOC), KS ⊂ Rn1 , formed by
The next important problem is the dual optimization problem, which
an n-dimensional vector q and a nonnegative scalar w is a convex set
is given by
defined by
maximize: bT y
KS  fw; q∶kqk ≤ w; q ∈ R ; w ∈ R gn
(7)
subject to: AT y  s  c;
Any convex quadratic inequality or norm inequality constraint can be s ∈ K where K  K (9)
expressed as a variable in a second-order cone, potentially by adding
a slack variable similar to w. For example, expressing the maximum in which the goal of the dual problem is to find a y ∈ Rp and
speed constraint is done as follows. First, a new slack variable vs is s ∈ K ⊂ Rn that maximize bT y, and the last constraint on s can be
prepended to the velocity vector to form an SOC: rewritten as s ∈ K because K is composed of purely self-dual cones
(i.e., positive linear cones and SOCs are self-dual). It is also useful to
h i note that the duality gap xT s  cT x − bT y ≥ 0 for any feasible
vs
∈ KS primal–dual pair x, (y; s) [21]. Also, when a strictly feasible primal–
vt
dual pair exists (i.e., a pair that satisfies the equality constraints and
lies strictly inside the cone K), the duality gap is zero for any optimal
and so vs ≥ kvtk by Eq. (7). Then, the maximum speed constraint is
primal–dual pair; that is, xT s  cT x − bT y  0 [22]. Therefore,
enforced by imposing the duality gap can be used to quantify the current iterate’s proximity
to the optimal solution.
vs ≤ V c
A. Interior Point Methods
The inequality constraint is converted into an equality constraint by
making use of one additional slack variable, ws ≥ 0: A primal–dual path-following IPM is used to solve the primal and
dual problems together [39,40]. A detailed discussion of IPM algorithms
vs  ws  V c can be found in [20,22,39–45]. In the following, the key components of
the IPM algorithm implemented in this research are given.
After assigning each PDG variable and necessary slack variable to a
1. Homogenous Self-Embedding
positive cone or SOC, these variables are collected into a global
solution variable x ∈ Rn . Finally, a straightforward, but tedious, This section presents a lifted version of the combined primal and
process produces the A matrix along with the b and c vectors such that dual problems that has two key benefits. The first is that there is a
Problem 3 is expressed in the following standard form [21,22]: readily available feasible solution. The second benefit is that the
solution of this lifted formulation fully describes the properties of the
original primal problem. Given an initial guess, (x0 , s0 , y0 , τ0 , κ 0 ), the
minimize: cT x
homogeneous self-embedded form of the SOCP [22,46], whose
subject to: Ax  b; relationship to the original primal and dual problems is clarified by
theorem 1, is
x∈K (8)
minimize: βν
in which c ∈ Rn maps the solution variable to a cost, A ∈ Rp×n
relates solution variables to constraint equations with b ∈ Rp on the subject to: Ax − bτ − rp ν  0;
right side, and K is given by − AT y  cτ − s − rd ν  0;
K  KlL × KS1 × : : : × KSm bT y − cT x − κ − rg ν  0;
rTp y  rTd x  rg τ  −β;
in which l and m are the resulting amount of positive cones and SOCs,
respectively. x; s ∈ K; τ; κ ≥ 0 (10)
DUERI ET AL. 201

in which ν ∈ R and y ∈ Rp are free and rp ∈ Rp , rd ∈ Rn , rg ∈ R, 3. Newton Search Directions


and β ∈ R are residuals [22,44] defined by Some terminology is needed to proceed with the solution
of the nonlinear system of Eqs. (11). Given a vector
Ax0 − bτ0 −AT y0  cτ0 − s0 v  v1 ; v2 ; : : : ; vn T ∈ Rn , we define the arrowhead matrix
rp ≜ ; rd ≜ ; to be
ν0 ν0
bT y0 − cT x0 − κ 0  
rg ≜ ; β ≜ −rTp y0  rTd x0  rg τ0  v1 vT2∶n
ν0 arrowv ≜
v2∶n Iv1
Indeed, rp , rd , and rg represent the infeasibility of the initial guess
Using this definition, we can replace the fourth equation in
and are zero if the initial guess happens to be feasible for the original
Eqs. (11) with
primal and dual formulations in Eqs. (8) and (9).
Remark 1: Using this formulation, a path-following algorithm can
be initialized trivially [22,44]. Any x0 and s0 that are in the interior of XSe  0 (12)
K serve as a strictly feasible, but not necessarily optimal, solution to
Eqs. (10). Moreover, because y is free, y0 can be taken to be a zero because it can be shown that xT s  0 ⇔ XSe  0, in which
vector of appropriate dimensions; finally, τ0 , κ 0 , and ν0 must be e  e1 T ; : : : ; ek T T ,
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

nonnegative and are typically chosen to be 1.


The following theorem summarizes the relationship between the X ≜ blkdiagarrowx1 ; : : : ; arrowxk 
original problem and the homogenous self-embedded formulation.
S ≜ blkdiagarrows1 ; : : : ; arrowsk 
Theorem 1: Consider the primal and dual problem given by

Eqs. (8) and (9). Let x; s; y; τ; κ be an optimal solution of the 0; j ≠ i;
homogenous self-embedded form in Eqs. (10). Then, one of the ei
j ≜ (13)
1; j  i
following conditions holds [22,26,44,46]:
1) τ > 0, κ  0. An optimal solution of the self-embedded
problem has been found. x∕τ is the optimal solution of the primal and xi represents the ith cone in the solution variable. That is, the
problem. block diagonal matrices are built from arrowhead matrices
2) τ  0, κ > 0, and bT y > 0. Primal is infeasible. corresponding to each cone in the solution variable. Without loss of
3) τ  0, κ > 0, and cT x > 0. Dual is infeasible. generality, the solution variable is arranged such that the linear cones
4) τ  0, κ  0. Problem is numerically ill-posed. are first, followed by the second-order cones. Because the linear
Complete proofs of this theorem can be found in [22,44], and so cones correspond to positive scalars, the first l elements of the block
they are omitted from this paper. diagonal matrices reduce to the diagonal elements.
Suppose that the current estimate of the solution is given by (x, s, y,
2. Central Path τ, κ). Then, the next iterate can be expressed as (x  Δx, s  Δs,
y  Δy, τ  Δτ, κ  Δκ). Applying this expression to Eqs. (11) and
To solve the nonlinear, homogenous, self-embedded problem in
substituting Eq. (12) into the fourth equality yields
Eqs. (10), a series of perturbed problems are solved. It can be shown
that finding the optimal solution to Eqs. (10) is equivalent to solving
the following system of bilinear equations for μ  0 [22,44,46]: AΔx − bΔτ  rp ν − Ax − bτ;
−A Δy  cΔτ − Δs  rd ν − −AT y  cτ − s;
T

Ax − bτ − rp ν  0;
bT Δy − cT Δx − Δκ  rg ν − bT y − cT x − κ;
−AT y  cτ − s − rd ν  0;
XΔSe  SΔXe  νμ0 e − Exs ;
bT y − cT x − κ − rg ν  0;
κΔτ  τΔκ  νμ0 − κτ − Eκτ (14)
xT s  0  μ;
κτ  0  μ; in which Exs ∈ Rn and Eκτ ∈ R are approximations (given
subsequently) to the second-order terms ΔXΔSe and ΔκΔτ,
μ  μ0 ν ≥ 0 (11) respectively. Also, the ΔX and ΔS matrices are formed in the same
fashion as X and S in Eq. (13). In its current form, the problem cannot
in which μ is a perturbation on the system of equations formed by be reliably and efficiently solved as shown in [44], and so cone
the constraints in Eqs. (10), ν becomes a given parameter, and μ0 is scalings are introduced that make it so.
given by
4. Nesterov–Todd Scalings
xT s  τ0 κ 0 Nesterov and Todd introduced a set of symmetric scalings that are
μ0  0 0 inexpensive to compute and make the problem numerically well
ml1
conditioned [47]. An important property of scaling matrices is that
The solution to the system of Eqs. (11) is unique for nonzero values of they do not change the cone or the central path. Consider the ith linear
μ [22]; therefore, for each positive μ, there exists a unique solution of or second-order cone and define scaling variables G  GT and θ ≥ 0
the system that can be found by using numerical techniques (such as as follows [47]:
Newton’s method). Moreover, as μ → 0 (or, equivalently, ν → 0), the s
solution of the perturbed problem converges to the solution of the siT Qsi
original problem in Eqs. (10). It is worth noting that the condition θ2 
xiT Qxi
μ  0 is a necessary and sufficient condition for the optimality of
convex programs and that it is equivalent to the Karush–Kuhn–
Tucker conditions for the lifted problem in Eqs. (10) [26,44]. The in which Q  1 for linear cones and
solutions (xμ , sμ , yμ , τμ , κ μ ) for any nonnegative μ define the central
path. The difference between one IPM and another lies primarily in Q  diag1; −1; : : : ; −1
how one tracks the central path toward the unperturbed system
solution. for second-order cones. Similarly, G  1 for linear cones and
202 DUERI ET AL.

e  qe  qT Given the above relationships, Δx; Δs; Δy; Δτ; Δκ are found by
G  −Q  first computing Δy and substituting it into Eqs. (17–20) as follows:
1  eT q

for second-order cones, in which AD2 AT  aa


 T1 Δy  l (21)

si ∕θ  θQxi in which


q  q
p
2xiT si  xiT Qxi siT Qsi 
−AD2 c − b r30
a  ; l  r10  AD2 c  b; r10  r1 − AD2 r20
The scaled cones are then a2 a2

x i  θGxi ; si  θG−1 si Equation (21) can be solved efficiently by making use of the
Sherman–Morrison formula [44,48]. Let P^  AD2 AT . Then it can be
This operation can be repeated for every linear and quadratic cone shown that the solution to Eq. (21) is found by solving the following
in the variables x and s. The scaled solution variables result from two linear systems for v0 and v1 :
concatenating all of the scaled cones to form x and s, producing
^ 0l
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

Pv (22)
x  ΘGx;
~ ~ −1 s
s  ΘG

in which Θ  diagθ1 ; : : : ; θk  and G~  blkdiagG1 ; : : : ; Gk .


Solving for x and s ^ 1  a
Pv (23)
~ −1 x;
x  ΘG  s  ΘG~ s (15) Substituting back into Eq. (21),
Substituting Eq. (15) into the fourth equality of the system in aT1 v0
Eqs. (14) leads to Δy  v0 − v
1  aT1 v1 1
AΔx − bΔτ  r1 ;
Note that P^ is a symmetric, positive definite matrix due to the
−A Δy  cΔτ − Δs  r2 ;
T
Nesterov–Todd scalings [47]; thus, a Cholesky factorization can be
used to solve the pair of linear equations. Furthermore, because both
bT Δy − cT Δx − Δκ  r3 ;
Eqs. (22) and (23) have the same coefficient matrix, one Cholesky
 G
XΘ ~ −1 Δs  SΘ ~ x  r4 ;
 GΔ factorization of P^ is sufficient to solve both equations. This offers a
significant advantage, because the Cholesky factorization is the most
κΔτ  τΔκ  r5 (16) computationally expensive part of solving Eqs. (16). In practice, P^ is
often a sparse matrix, and so sparse techniques further reduce solver
where, as in [44], runtimes, as discussed in Sec. IV. However, a method for obtaining
Exs and Eκτ is still needed and is presented next.
r1  rp ν − Ax − bτ; r2  rd ν − −AT y  cτ − s;
r3  rg ν − bT y − cT x − κ; 5. Mehrotra Predictor–Corrector
A predictor–corrector scheme is used to estimate the second-order
r4  νμ0 e − Exs ; r5  νμ0 − κτ − Eκτ
terms that arise from the nonlinear system of Eqs. (16) and to update
the centering term ν. The Mehrotra predictor–corrector method
Given the current solution (x, s, y, τ, κ), Exs , and Eκτ , one can [39,40] has been shown to have excellent convergence properties in
compute r1 through r5 . practice while still being inexpensive to compute. During the
Rearranging the last equality in Eqs. (16), prediction step, Exs and Eκτ are set to be zero; these values are then
used to solve the system of Eqs. (16). At this point, a scaling term
r5 − κΔτ
Δκ  (17) 0 < α ≤ 1 is computed such that the next solution does not deviate far
τ from the central path. There are many strategies for selecting this
The fourth equality in Eqs. (16) implies that scaling term, but we employ the maximum Newton step-size method,
which computes the value of α for each cone such that the next iterate
 −1 r4 − ΘG is in the interior of the cone:
Δs  ΘG
~ X ~ 2 Δx (18)

~ −1 . Then it can be shown that the following relations α  minfrαx ; rαs ; rατ ; rακ ; 1g
Let D  ΘG
also hold [44]:
in which 0 < r < 1 is close to one (e.g., r  0.995), and αx , αs , ατ , and
κ are the maximum values of α such that
Δx  D2 r20  AT Δy − cΔτ (19)
xαx Δx ∈ intK; sαs Δs ∈ intK; ατ τ Δτ > 0; κ ακ Δκ > 0

r30  aT1 Δy The value of α can further be reduced to keep the next iterate in a
Δτ  (20) prescribed neighborhood of the central path, for example, by using
a2
self-regular proximity measures as in [22]. For the PDG problem,
in which however, further limiting was not needed because convergence is
reliable with the maximum Newton step-size method.
r5 After the predicted search direction is obtained, the predicted
r20  r2  ΘG  −1 r4 ;
~ X r30  r3   cT D2 r20 ;
τ complementarity gap is
κ
a1  −b  AD2 c; a2   cT D2 c gp  x  αΔxp T s  αΔsp   κ  Δκ p τ  Δτp 
τ
DUERI ET AL. 203

in which subscript p indicates the solution with Exs and Eκτ equal to Embedded systems typically operate in environments with stringent
zero. The new centering parameter ν is then taken to be [44] real-time requirements and limited memory. Many problems that
 2 naturally occur in engineering tend to translate into sparse optimization
gp gp problems, such as discretized control problems [50]. For this reason, a
ν T (24)
x s  κτ k  1 solver should minimize memory usage and number of arithmetic
operations by leveraging the problem structure and sparsity. Moreover,
The predicted Newton directions are then used to approximate the autonomous systems rely on the results of onboard optimization to
second-order terms: safely operate, and so it is also important to minimize logical branches
for ease of verification as well as for increased computational speed.
Exs  ΔX~ p ΔS~p e (25) In general, sparse linear algebra operations (like sparse matrix–
matrix multiplication) reduce the total number of elementary
operations but increase the cost of each operation; in other words, the
number of operations is reduced by avoiding the addition and
Eκτ  Δκ p Δτp (26) multiplication of zeros, but it is necessary to determine how the
remaining nonzero elements interact. In explicit coding, software is
where automatically generated to perform certain specific, otherwise
computationally expensive, tasks. Thus, much of the logic associated
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

with sparse computations can be avoided by hard coding these


ΔX~ p  blkdiagarrowΔx~1 k
p ; : : : ; arrowΔx~p ;
operations. For PDG, both a generalized SOCP solver has been
ΔS~p  blkdiagarrowΔs~1 k
p ; : : : ; arrowΔs~p ; implemented in C++ per Sec. III and a capability for automatically
generating a customized solver has been implemented in ANSI-C.
Δx~p  ΘGΔx
~ p; ~ −1 Δsp
Δs~p  ΘG
A. Sparsity
The updated second-order approximations and the new centering
As discussed in the preceding section, solving the PDG
parameter are then used to solve Eqs. (16) again [39,40]. Because the
coefficient matrix P^ is unchanged, the factorized matrix from the optimization problem reduces to solving a pair of related linear
prediction step is reused. systems of equations, Eqs. (22) and (23). Because P^ is a symmetric,
positive definite matrix, a Cholesky factorization is performed to
obtain
B. Algorithm Overview
The entire IPM algorithm that is being customized is P^  L^ L^ T (27)
summarized below.
in which L^ is a lower triangular matrix. To speed computation, the
^ which
goal is to reduce the number of nonzero elements present in L,
Data: a tolerance, ϵ, an initial point (x0 , s0 , y0 , τ0 , κ 0 ) as described above, depends on the sparsity pattern (i.e., the location of nonzero
and the problem structure given as: A, b, and c. elements) of P.^ Therefore, a permutation matrix R is sought that
Result: an optimal solution, (x , s , y , τ , κ ) reduces the number of nonzero elements in the Cholesky
begin ^ giving the new
factorization by a similarity transform of P,
x  x0 , τ  τ0 , y  y0 , s  s0 , κ  κ0
while xT s  κτ > ϵ do factorization matrix L:
predict: solve Eqs. (16) with ν  0, Exs  0, Eκτ  0
calculate Newton step size, α ^ T  LLT
RPR (28)
update ν, Eq. (24)
correct: solve Eqs. (16) with Exs , Eκτ in Eqs. (25) and (26) in which L is a lower triangular matrix with a reduced number of
calculate Newton step size, α nonzero entries. The approximate minimum degree method [49] is
x  x  αΔx, τ  τ  αΔτ
y  y  αΔy, s  s  αΔs used to obtain an R that is both inexpensive to compute and effective
κ  κ  αΔκ at reducing the number of nonzero elements in L. Substituting
if τ > 0 then Eqs. (27) and (28) into Eq. (22) gives
x  xτ , s  sτ
y  yτ , τ  τ LLT Rv0  Rl (29)
κ  κ
else if κ  0 then Problem is ill posed in which RRT  I, and the Cholesky factorization and corresponding
else if cT x < 0 then Dual is infeasible
else if bT y > 0 then Primal is infeasible
forward/back substitutions have a reduced number of nonzero entries
to process. A similar transformation can be done to the linear
equation Eq. (23) to obtain

LLT Rv1  Ra (30)


IV. Solver Customization
The methods developed to generate efficient, customized C code in which L and R are the same as in (32).
for specific SOCP problem classes (formally defined below) are
presented here, along with the benefits of customized code. This B. Memory Allocation and Explicit Coding
customization enabled an onboard implementation of the fully Much of the computational effort associated with sparse linear
constrained PDG [24,29]. Two methods are used to increase algebra stems from not knowing the problem structure beforehand
computational speed: approximate minimum degree [49] and explicit and therefore having to dynamically determine which nonzero
coding [23,24,45]. While both methods have been explored in elements interact every time an operation is carried out. However, a
different problems, explicit coding has not previously been applied in given embedded system typically solves problems with a uniform
IPMs to solve SOCPs, which is our first contribution. Thus, the structure; that is, the locations of most nonzero elements in A, b, and c
analysis in this section can be thought of as an extension of [23,25] to do not change. For example, changing the initial conditions in the
SOCPs. Further, to the best of our knowledge, this is the first time that PDG problem does not affect the structure of A, b, or c. To take
customization has been used to enable software capable of real-time, advantage of this fixed structure, a problem class is formally defined
optimization-based onboard guidance for planetary PDG. as follows.
204 DUERI ET AL.

Definition 3: Given A0 ∈ Rp×n , b0 ∈ Rp , c0 ∈ Rn , and K0 ⊂ Rn , and an arbitrary v ∈ R2 such that v   v1 v2 T . A


a problem class, P, is defined as u   u1 u2 T  Rv can be computed without any explicit
multiplications by treating the operation as a mapping:
P  fA ∈ Rp×n ; b ∈ Rp ; c ∈ Rn ; K ⊂ Rn ∶strA ≤ strA0 ; u1  v2 ; u2  v1
strb ≤ strb0 ; strc ≤ strc0 ; K  K0 g
These mappings are also hard coded into the generated C code and
help reduce the complexity of the runtime operations.
in which the ≤ operator denotes elementwise inequality and “str” As problem size increases, the amount of C code that is generated
maps any nonzero element to a 1 and leaves 0 elements undisturbed, grows rapidly. Therefore, the sheer amount of machine instructions
thereby forming the sparsity structure of its input. Thus, any A that is causes instruction cache misses that eventually outweigh the
more sparse than A0 is also in P if any zero element in A0 is also a zero algorithmic advantages of avoiding sparse logic. For this reason,
element in A (similarly for b and c). customization is best suited for small-to-medium problem sizes
Without loss of generality, assume that a given embedded system (1–1000 solution variables), as observed empirically in Sec. VI.
solves a set of problems, P 0 ⊆ P. Then, the problem class, and Therefore, the customization described herein is beneficial for real-
therefore an upper bound on the sparsity structure, is known and world applications with around 1000 solution variables or less.
implementing a generic solver on an embedded device is wasteful. Increasing the effectiveness of this type of code generation for larger
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

Because the problem size is known, the exact amount of memory that problems is the subject of ongoing research; however, it is noted that
is necessary to solve P is statically allocated, removing the need for the authors have successfully and repeatedly landed a rocket using
dynamic memory allocation altogether. This property is highly approximately 750 variables.
valued in aerospace engineering software development practice. It
eliminates memory leaks and overflows, and, more important,
reduces the complexity of flight software verification. V. Maximum-Divert Powered-Descent Guidance
Furthermore, the generated code is free of the logical operations In this section, the preceding convexification results are extended
introduced by sparse algorithms. This is accomplished by keeping to show that the control convexification presented in Sec. II.B is
track of nonzero element interactions and generating code that lossless when both the state constraints and the thrust-pointing
handles sparse operations directly. That is, once the interaction constraints are simultaneously active. The primary objective is to
between two nonzero elements has been determined, one line of C theoretically validate the control convexification used to obtain the
code is generated to directly and correctly handle the interaction trajectories that were flown in 2012–2014.
without any logic. Figure 2 illustrates the procedure for generating a First, a theoretical extension of the PDG algorithm is presented. The
customized solver for a given problem class. This customized sparse need for this extension was encountered during the terrestrial test flights
framework supports the IPM algorithm described in Sec. III, which is of the customized PDG algorithm [51]. Specifically, the speed of the test
also included in the generated code. rocket in lateral flight was limited to 90 km∕hr. While performing the
Explicit coding is also used to avoid certain expensive operations, one kilometer divert, the rocket would reach this speed limit and then
such as finding a suitable R via AMD and some matrix remain at it, even for segments with active thrust-pointing constraints;
multiplications. Note that R in Eq. (28) depends only on the sparsity that is, the speed and thrust-pointing constraints were simultaneously
structure of P^ [49]. Further, recall that P^  AD2 AT , strA is active. Previous results for lossless control convexification of the
bounded from above by some A0 , and strD relies solely on K  K0 . constrained PDG problem [19,32] did not include simultaneously active
Thus, there is an upper bound on strP ^ for each problem class. The thrust-pointing and speed constraints. Further, the thrust-pointing
permutation matrix corresponding to this upper bound is found when constraint can also be continuously active. Hence, the lossless
the custom solver is generated and is then hard coded into the solver. convexification results for the PDG problem, which theoretically prove
Furthermore, because R represents a similarity transformation, the that the solution of the convexified problem is also an optimal solution
matrix multiplication RPR ^ T in Eq. (28) and all of the matrix-vector for the original nonconvex PDG problem, must be extended to include
continuously and simultaneously active thrust-pointing and speed
multiplications involving R in Eqs. (29) and (30) are treated as known
constraints.
elementwise mappings. For example, given a similarity mapping,
Second, near term planetary exploration missions may leverage
  existing landing systems, thereby limiting the amount of propellant
0 1
R available for diverts. For so-called multi-X landing strategies [31], in
1 0 which the divert goal is not to reach the center of a landing ellipse but

Fig. 2 Flow diagram for explicit code generation.


DUERI ET AL. 205

Table 1 A History of lossless convexification results


Year Result
2007 Minimum-fuel control convexification without active state constraints or thrust-pointing constraints [8]
2008 Minimum-landing-error control convexification with active state constraints for at most one instant and without thrust-pointing constraints [10]
2013 Minimum-landing-error control convexification with thrust-pointing constraints, but without active state constraints [9]
2013 Maximum-divert control convexification with velocity constraints active over finite time intervals, but without thrust-pointing constraints [19]
2014 Control convexification for general linear systems with active polytopic state constraints, but without thrust-pointing constraints [32]
2015 Maximum-divert control convexification with simultaneously active thrust-pointing and velocity constraints proven in this text

simply to escape large, known hazards in the landing ellipse, it is maximum conditions, complementary slackness conditions, and
beneficial to determine the largest divert possible given a fixed transversality conditions. The Hamiltonian and the Lagrangian are
amount of propellant [19].
As a result, the extension of lossless convexification for the PDG Htpr tT vtpv tT Tt∕mt−g−αpm tΓt (31)
problem with simultaneously and continuously active speed and
thrust-pointing constraints is presented for the maximum-divert PDG
Lt  Ht  λ1 tkTtk2 − Γ2 t  λ2 tρ1 − Γt
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

problem. A history of previous convexification results is presented in


Table 1, with the 2015 result presented in this paper concluding the  λ3 tΓ − ρ2   λ4 Γ cos θ − n^ T Tt  νtkvtk2 − V 2c 
table. Posing Problem 4 as a maximum-divert PDG problem
facilitates this extension and is valid for minimum-fuel PDG with costates pr , pv , and pm and Lagrange multipliers λi and ν. The
problems that require the entire fuel allocation to reach the landing costate equations are
site (i.e., landing sites that correspond to maximum diverts). This
theoretical extension provides the analytical basis for the use of the p_ r t  0;
convex PDG algorithm demonstrated in the terrestrial test flights
[51], because the resulting trajectories use all of the onboard p_ v t  −pr t − 2νtvt;
propellant to reach the maximum-divert distance.
p_ m t  pv tT Tt∕m2 t
The convexified maximum-divert problem is given next as
Problem 4. The cost is changed with respect to Problem 2 to reflect
the new objective. Also, two simplifications are made to the The transversality conditions are
constraint set in Problem 4: 1) the terms relating to planetary rotation
are dropped because both the time horizon and the initial altitude of pr tf   −e1 p0 w1 − e2 p0 w2  e3 ξr3 ;
the vehicle during the terrestrial tests are small, and 2) the glideslope pv tf   ξv  2μvtf ;
constraint is removed because the terrestrial trajectories flown by the
test vehicle did not activate this constraint. Removing these con- pm tf   −ζm
straints simplifies the theoretical analysis while still maintaining a
constraint set that is representative of the terrestrial test trajectories. The stationary conditions are
Indeed, having active state constraints complicates the convex-
ification proofs (see [32]). This issue is further compounded by the ∂T Lt  pv t∕mt  2λ1 tTt − λ4 n^  0;
fact that active thrust-pointing constraints modify the feasible control
space such that not all boundary points of the feasible control space ∂Γ Lt  −αpm t − 2λ1 tΓt − λ2 t  λ3 t  λ4 t cos θ  0
are extremal points. In the maximum-divert problem, it is the velocity
constraint that becomes active, quite often together with the active The pointwise maximum principle states the following:
control constraints (e.g., veloctiy-bound and thrust-pointing
constraints). The subsequent proof establishes convexification for maximize: pTv tTt∕mt − αpm tΓt
this case, which is the main theoretical contribution relevant to the subject to: ρ1 ≤ Γt ≤ ρ2 ; kTtk ≤ Γt; Γt cos θ ≤ n^ T Tt
tested landing maneuvers.
Problem 4: Convex Relaxation of the Controls in the Maximum-
Divert PDG Problem And last, because the final time is free and the Hamiltonian does not
depend explicitly on time, it is identically zero along the optimal path,
minimize∶ J  −w1 r1 tf  − w2 r2 tf 
subject to∶ rt
_  vt; rt0   r0 ; r3 tf   0 Ht  0 ∀ t ∈ 0; tf  (32)
vt
_  Tt∕mt − g; vt0   v0 ; vtf   0
Theorem 2: The thrust magnitude constraint holds with equality;
_  −αΓt;
mt mt0   m0 ; md ≤ mtf  that is, kTtk  Γt ∀ t under the following three assumptions:
n^ T Tt ≥ Γ cos θ; kvtk2 ≤ V 2c 1) The angle θ defining the pointing cone is not π∕2 (i.e., cos θ ≠ 0).
2) The unit vector n^ defining the pointing cone is not orthogonal to
kTtk2 ≤ Γ2 t; ρ1 ≤ Γt ≤ ρ2 the gravity vector g (i.e., n^ ⊥ g).
3) The thrust magnitude constraints and vehicle weight satisfy the
As in Sec. II.B, the goal is to show that any optimal solution of inequality ρ1 ≤ mtg ≤ ρ2 for all t.
Problem 4 satisfies kTtk  Γt; that is, the convexification of the Proof: Proceeding by contradiction, assume there exists an interval
control constraints is lossless. In other words, optimal solutions of the t1 ; t2  ⊂ t0 ; tf  for which kTtk < Γt for all t ∈ t1 ; t2  under
convexified problem are optimal solutions of the original nonconvex suitable restrictions on the control functions [19,32]. The standard
problem. complementary slackness condition then implies that the multiplier
The proof relies on a maximum principle with state constraints as λ1 t  0 on the interval. The preceding stationary conditions then
in [19,33]. Note that, due to the increased complexity of the reduce to the following:
maximum principle, convexification results in the presence of active
state constraints are harder to obtain. The maximum principle with pv t∕mt  λ4 n^
active state constraints states all of the necessary conditions for
optimality, including the state and costate equations, pointwise −αpm t − 2λ1 tΓt − λ2 t  λ3 t  λ4 t cos θ  0
206 DUERI ET AL.

Note that, if the pointing constraint is satisfied with strict inequality, complementary slackness), and hence ν_ t  0. Thus, the first term is
then λ4 t  0 and the proof in [19] is recovered. As such, it is always zero. Hence, either νt  0 or vt
_  0. Each case is now
assumed that the pointing constraint holds with equality throughout considered.
the remainder of the proof; that is, Case 1: Suppose that νt  0. Then pr t  0 because
p_ v t  0. The first transversality condition implies p0  0.
n^ T Tt  Γt cos θ (33) Additionally, the Hamiltonian can be rewritten as

Then, using assumption 1, one obtains Γt  n^ T Tt∕ cos θ. Ht  χtTt − pTv tg  0
As a result, the pointwise maximum principle becomes
 
n^ T Because the switching function χ t  0, it must be that
maximize: pTv t∕mt − αpm t Tt pTv tg  0. Note that pv t is aligned with the unit vector n. ^ By
cos θ
assumption 2, n^ is not orthogonal to g, and hence pTv tg  0 implies
subject to: ρ1 ≤ Γt ≤ ρ2 ; kTtk ≤ Γt pv t  0. This subsequently implies that pm t  0, which violates
the nontriviality condition of optimal control (see theorem 15 in
Upon defining the switching function, [32]). Hence, νt ≠ 0.
Case 2: Suppose νt ≠ 0, which implies that the velocity con-
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

pTv t n^ T straint is active. This means that v_ T tvt  0, and hence vt
_ 0
χ t  − αpm t
mt cos θ [using Eq. (38)]. Then Tt  mtg. The pointwise maximum
condition reduces to
it is clear that kTtk  Γt whenever χ t ≠ 0 because the
(maximizing) cost function drives optimal values of Tt to the maximize∶ − αpm tΓt
kTtk ≤ Γt constraint boundary, thereby making it an equality.
Thus, assume χ t  0 on an interval; this implies that the cost subject to∶ ρ1 ≤ Γt ≤ ρ2 ; kTtk ≤ Γt; n^ T mtg  Γtcos θ
function equals zero. Solving for pv t when χ t  0 gives
by using Eq. (33). If pm t > 0, then Γt should be made as small as
n^ possible (i.e., Γt  kTtk). In the following, it is proven that this is
pv t  αmtpm t the case. Combining Eqs. (31) and (32) with Tt  mtg,
cos θ

along with pTr vt  αpm tΓt

αpm t α pTv tTt Note that, because p_ v t  0, pr  −2νtvt. Thus,
λ4 t  and λ_ 4 t  (34)
cos θ cos θ m2 t
−2νtkvtk2  αpm tΓt
Differentiating pv with respect to time gives
Because νt < 0, kvtk > 0, α > 0, and Γt > 0, it must be that
pm t > 0. Thus, kTtk  Γt and ρ1 ≤ kTtk ≤ ρ2 by
p_ v t  mtλ
_ 4 t  mtλ4 tn
_ ^ (35) assumption 3, which contradicts the original hypothesis. Thus, it
has been shown by contradiction that the thrust magnitude constraint
This implies that p_ v t is a vector along n.
^ Substituting Eq. (34) into holds with equality everywhere along the optimal trajectory.□
Eq. (35) and taking the norm yields Finally, as in Sec. II.C, the time-varying mass dynamics can be
rigorously approximated with convex dynamics and constraints [8–
kp_ v tk  jmtλ
_ 4 t  mλ4 tj;
_ 10]. The resulting convexified maximum-divert PDG problem is then
 
 pm t pTv tTt  given by Problem 5.

 − α Γt
2 α ;
cos θmt
For cases in which the target landing site uses all available fuel (as
cos θ
  is the case with the terrestrial test flights), the lossless convexification
α  pTv tTt has been proven when the speed and thrust-pointing constraints are
 − αΓtp t  (36)
j cos θj m
mt  simultaneously active. Thus, Problem 5 produces the same solutions
as Problem 1.
Next, note that χ t  0 ⇒ χ tTt  0, which combined with Problem 5: Convex Relaxation of the Maximum-Divert PDG
Eq. (33), implies that Problem

pTv tTt αpm tn^ T Tt minimize∶ J  −w1 r1 tf  − w2 r2 tf 


χ tTt  − ;
mt cos θ subject to∶ rt
_  vt; rt0   r0 ; r3 tf   0
pT tTt αΓtpm t cos θ vt
_  ut − g; vt0   v0 ; vtf   0
 v − ;
mt cos θ
z_t  −ασt; zt0   ln m0 ; ln md ≤ ztf 
pTv tTt
 − αΓtpm t  0 (37) n^ T ut ≥ σt cos θ; kvtk2 ≤ V 2c
mt
kutk2 ≤ σ 2 t; ρ1 e−z0 1 − zt − z0 t ≤ σt
Consequently, it is clear that kp_ v tk  0 by substituting Eq. (37)
into Eq. (36). Then, p_ v t  0 and p v t  0 on the interval. σt ≤ ρ2 e−z0 1 − zt − z0 t
From [19], premultiply p v t with vt,
_ giving

v_ T tp v t  v_ T t−p_ r t − 2_νtvt − 2νtvt


_ VI. Numerical Results
 −2_νtv_ T tvt − 2νtv_ T tvt
_ 0 (38) In this section, several numerical examples are used to demonstrate
the effectiveness and performance of both the customization
If the velocity constraint is active, dvtT vt∕dt  2vt
_ T vt  methodology and theoretical results.
0 in the interval, then the first term is zero and consequently also First, in Sec. VI.A, lossless convexification for PDG with
vt
_  0. If it is inactive, then νt  0 in the interval (due to simultaneously and continuously active speed and thrust-pointing
DUERI ET AL. 207

Table 2 Simulation parameters to activate over continuous intervals of the trajectory. The PDG
parameters of Table 2 are used.
Parameter Value
For the fuel optimal PDG problem, the lander begins at an altitude
g 0 0 3.7114 T m∕s2
of 2 km and must traverse approximately 8 km to reach its final
m0 2000 kg
mf 1700 kg destination at the origin. This final condition forces the lander to
n^  0 0 1 T travel over a horizontal distance that is four times greater than its
θ 45 deg altitude (Fig. 3). Moreover, the fuel allocation is selected so that the
ρ1 2500 N vehicle runs out of fuel just as it lands, making the origin one of its
ρ2 25000 maximal diverts.
I sp 220 s Figure 4 shows that the velocity constraint is active over a
Vc 130 m∕s continuous interval of the trajectory (between approximately 60 and
r0  7000 4000 2000 T m
v0  120 0 −50 T m∕s 84 s). In addition, the thrust-pointing constraint is active at the same
time as the velocity constraint from 60 to 74 s. Thus, this trajectory is
an example of the convexification theory presented in this paper.
The lower and upper thrust constraints are satisfied, despite the fact
constraints is demonstrated. A divert trajectory is planned using the that the lower thrust bound originally defined a nonconvex thrust
convexified PDG algorithm of Problem 5. All of the constraints are regime (Fig. 5). Thus, the convex relaxation of the control space is a
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

satisfied, thereby showing that the solution of the convexified lossless convexification of the original, nonconvex problem, despite
problem is a feasible solution of the original nonconvex Problem 1 . having continuous subarcs of active velocity (state) constraints in
Because the convexified problem is a relaxation of the original addition to simultaneously active thrust-pointing constraints.
problem, all solutions of Problem 1 are also solutions of the Finally, the trajectory for a problem with the same initial
convexified problem. Thus, it suffices to show that the optimal conditions and constraints is obtained by switching to the maximum-
solution to the relaxed problem is feasible for the original problem to divert cost function defined in Problem 5. The differences between
show that it is also an optimal solution of the original problem. the two trajectories are tiny and reflect the convergence tolerances for
Second, in Sec. VI.B, the effectiveness of the general IPM for the solvers (Fig. 6). This result was expected because maximum-
SOCPs of Sec. III and the advantages of customization as described divert problems are also minimum-fuel problems when fuel is the
in Sec. IV are demonstrated. For a range of PDG problem sizes, the limiting factor for the trajectory (and it typically is).
general IPM and customized IPMs are compared with several
publicly available and noncustomized IPMs for SOCPs. The PDG
problem size is changed by increasing the number of discrete time
steps. A customized IPM is automatically generated for each PDG
problem size using the methods in Sec. IV.
In short, the general IPM presented in this paper achieves the same
runtimes as the best of the publicly available IPMs for small-to-
medium problem sizes. The customized solver is twice as fast as
general IPMs for the smallest problems, which decreases to a 10%
speed advantage for medium-to-large problems. This decrease is
expected, as discussed in Sec. IV: eventually, the increased rate of
instruction cache misses outweighs the benefits of eliminating the
logic and for-loops of the noncustomized sparse linear algebra
routines.
Finally, in Sec. VI.C, the runtime performance of the customized
IPM is characterized on a 200 MHz flight processor. Runtimes on the
order of 0.7 s are achieved, which are suitable for using the PDG
algorithm onboard a lander.

A. Example of Convexified PDG Fig. 4 Velocity and thrust-pointing profiles for fuel optimal trajectory.
A Mars powered-descent scenario is considered with a When n^ T u  kuk cos θ, the thrust-pointing constraint is active. Dashed
conservative velocity upper bound to force the velocity constraint lines represent constraint boundaries.

4000

3000
z (m)

2000

1000

10000
0
4000
3000 5000
2000
1000
0 0 x (m) Fig. 5 Thrust magnitude and mass time histories. The thrust upper
y (m) and lower bounds are represented by dashed and dash-dotted lines,
Fig. 3 Three-dimensional overview of fuel optimal trajectory. respectively.
208 DUERI ET AL.

−1 ECOS
10
General Bsocp

Log Mean Runtime (s)


Custom Bsocp

−2
10

500 1000 1500 0 2000


Solution Variable Size
Fig. 7 Planetary landing benchmark for real-time solvers and problems
of small-to-medium size.
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

Fig. 6 Percent differences between fuel optimal and maximum-divert


solutions.

Log Mean Runtime (s)


0
10
B. Solver Performance
In this subsection, the solver developed here (called Bsocp) is
compared with several other well-known solvers in terms of runtime
performance. Every problem class is run 500 times, and the average −2 SDPT3−v4.0
10
runtime on a workstation with an Intel Core i7 (3.4 GHz) processor SeDuMi
and 15 GB of RAM is presented. ECOS
SDPT3 [52], SeDuMi [53], ECOS [26], Bsocp, and customized General Bsocp
solvers are used over a range of problem sizes to find optimal −4 Custom Bsocp
solutions of the planetary soft-landing problem described herein. The 10
0 5000 10000 15000
problem size is varied by increasing the number of points in the Solution Variable Size
discretization of the dynamics [8]. Table 3 shows the types of cones Fig. 8 Planetary landing benchmark with broader range of solvers and
used in the performance comparisons of Figs. 7 and 8. All SOCs are problem sizes.
four dimensional.
For small problems (1–1000 solution variables), the customized
solvers solved the problems about two times faster than the Bsocp C. Performance on a Flight Processor
solver (Fig. 7). Problems with about 2000 solution variables gain As shown in Sec. VI.B, solution times on the order of milliseconds
almost no advantage by customization, as expected. ECOS and to tens of milliseconds are possible for smaller problem sizes when
Bsocp performed similarly for small-to-medium problems, with each run on a 3.4-GHz desktop processor. For planetary landing, however,
taking turns outperforming the other over different regions. PDG would be expected to run on a radiation-hardened flight
For problems with more solution variables than that of the processor. As an example of a flight processor, the Mars Science
simulations shown in Fig. 7, instruction cache misses dominate any Laboratory used a BAE RAD750 PowerPC for its entry, descent, and
gains from customization. For this reason, benchmarking results are landing. This flight processor currently has a clock speed on the order
shown for larger problems without customized solvers. As one can of 200 MHz.
see from Fig. 7, ECOS scales better than Bsocp for problems with Therefore, for eventual landing applications on bodies other than
more than about 10,000 solution variables. This trend is due to the the Earth, it is important to characterize the runtime of a
linear algebra libraries in Bsocp not being intended for larger representative PDG problem on a flight processor. Primarily because
problems. Nonetheless, Bsocp outperforms SDPT3 and SeDuMi for of differences in instruction sets (x86 processors are Complex
all problem sizes in the benchmark. instruction set computing (CISC) or hybrid, whereas the PowerPC is
Reduced instruction set computing (RISC)) and memory access
speeds, a PDG runtime on a desktop processor cannot simply be
scaled by clock speed to a flight processor (i.e., increasing the
Table 3 Benchmark detailsa
runtime on a desktop by a factor of 3000 MHz/200 MHz).
Number of KL Number of Ks Hence, we ran a convexified PDG algorithm in C on a 200 MHz
n cones cones RAD750 that is part of a flight software testbed at NASA Jet
320 153 49 Propulsion Laboratory. The experimental setup of the runtime
567 270 88 characterization is discussed first and then the results.
757 360 118
1,137 540 178 1. Setup of Runtime Experiment
1,327 630 208
1,612 765 253 First, the real-time operating system used in the experimental setup
1,897 900 298 is VxWorks. The only other process running on the processor is the
3,797 1,800 598 Ethernet driver, and so the PDG has as close to 100% of the processor
9,497 4,500 1,498 as practically possible.
15,197 7,200 2,398 Second, note that a convexified PDG algorithm consists of a parser
a
that translates the guidance problem and data into an SOCP and a solver
The variable n represents the solution variable
that solves the resulting SOCP in standard form as in Eq. (8). For this
size, number of KL cones represents the
number of linear cones in the solution variable,
runtime characterization, the parser is discussed in the companion
and the number of Ks cones represents the paper [31]. This parser is written in C and includes approximations to
number of second-order cones in the solution the standard Problem 3 that reduce runtime. For example, at each
variable. timestep the SOC for the glideslope constraint is replaced with several
DUERI ET AL. 209

tangent planes. The SOC for the speed constraint remains. Runtime possible. An active constraint has at least one time step in which the
data were collected for both the parser and the solver. associated slack variable is zero. Colloquially, the solution “rides”
Third, for the purposes of comparison with results in Sec. IV.B, the each inequality constraint at least once.
problem’s size parameters are n  403, the number of KL cones is The stressing problem is a speed-limited divert, as discussed in the
263, and the number of KS cones is 35. All KS are four dimensional. companion paper [31]. The maximum-thrust-angle, maximum-speed,
In addition, there are 286 equality constrains, which is the number of and maximum-thrust constraints are all active. Because of the desire to
rows in A in Eq. (8). This problem size lies approximately between activate the maximum-speed constraint (it is the sole SOC state
the first two points of Fig. 7. However, as noted, there are fewer constraint), the resulting divert trajectory approximates a straight line
second-order cones than in the benchmark problem. from initial position to final position. This straight-line behavior, in
Fourth, a stressing instantiation of the PDG problem is desired. turn, necessarily deactivates the glideslope constraint. The behavior
“Stressing” in this context does not mean size: given the speed of also deactivates the minimum-thrust constraint as follows. The thrust
flight processors, a smaller-size problem would likely be flown. profile is essentially “bang-off-bang” in magnitude. During the “off”
Instead, the goal is to have as many inequality constraints active as portion, the vehicle is coasting at maximum speed with thrust that
cancels weight. Because the minimum thrust is less than the vehicle
weight at all points in the trajectory, allowing the vehicle to “fall,”
minimum thrust is never needed.
Fifth, because the stressing problem rides the maximum-speed
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

constraint, the minimum-time solution is empirically determined to be


the minimum-fuel solution. That is, considering the propellant mass
needed to divert as a function of time of flight, if the time of flight is less
than some t , the resulting PDG problem is infeasible. Above t , the
propellant mass increases monotonically to the physical limits of
problem (mass must remain positive). See Fig. 9. The relevance of this
behavior to runtime characterization is explained subsequently.
Fig. 9 Optimal propellant as a function of time of flight for a small, Sixth, runtime varies with whether a given time of flight is infeasible
stressing PDG problem.
or feasible. Moreover, if the time of flight is feasible, runtime varies

Fig. 10 Performance of the customized solver on a flight processor for a small, stressing PDG problem as a function of time-of-flight.
210 DUERI ET AL.

with distance to the feasibility boundary. If the time of flight is the whole processor to itself, but would be running in the background
infeasible, the runtime to certify infeasibility can also vary widely. with, for example, 25–30% processor availability. In this case, the
Therefore, the runtime characterization is for a range of times of flight effective runtime per time of flight increases to approximately 2.5 s,
from well within the infeasible range to well within the feasible range. which is still suitable for onboard implementation [54].
For this problem, a value of t  42.1748 s was empirically
determined. Note that this value will vary with the number of points in
the time discretization. The times of flight tested are centered on this VII. Conclusions
t and go from 29.7998 s to 54.5498 s in 0.25 s steps, producing 100 Convexification theory has been extended for maximal-divert
times of flight. These times of flight stretch sufficiently far into the PDG problems to allow for continuously active state constraints in
feasible range for the runtime to exhibit a steady-state behavior. addition to simultaneously active thrust-pointing constraints. This
Similarly, they stretch far enough into the infeasible range that the theoretical achievement enabled terrestrial test flights, in which the
apparent variations in runtime are captured. Also, these times give velocity constraint is active for continuous intervals along the
both an infeasible and a feasible time of flight within 0.125 s of t . trajectory. Furthermore, a fast and reliable solver implementation was
Seventh, to average out any runtime variations due to intermittent developed in order to exploit the lossless convexification of the
maintenance tasks of the operating system, the PDG calculation is problem in real time and onboard the test vehicle.
repeated 25 times for each of the 100 times of flight. Finally, the developed solver, in both general and custom imple-
Finally, a complication in compiling the customized solver for the mentations, was demonstrated on a radiation-hardened flight processor.
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

target processor and operating system was that the default As might be expected in practice, the solver runtimes for a small,
optimization level -O0 had to be used for reliable performance. stressing powered-descent guidance problem were characterized.
Nonetheless, many other individual optimization flags were Future work will include tailoring the customization to unique aspects
enforced, as well as the appropriate -march option. of flight processors and performing a more extensive characterization of
runtime across a range of powered-descent scenarios. Nonetheless, it
2. Runtime Results has been shown that even running in the background on a flight
The main result is shown in Fig. 10a, which shows mean runtimes processor, an optimal powered-descent trajectory could be calculated in
for the customized solver for the stressing PDG problem as a function approximately 2.5 s, which is attractive for onboard implementation. In
of time of flight. Mean solver runtimes vary between approximately short, it may be argued that the initial feasibility of solving for a
0.4 s and 1.3 s for solutions with duality gaps that are less than powered-descent trajectory onboard a spacecraft using real-time convex
1 × 10−9 . Observe that simply scaling a 3 ms runtime from Fig. 8 by optimization has been demonstrated, maturing the technology readiness
3.4 GHz/200 MHz gives 0.051 s, which underestimates the runtimes level of the proposed method.
by an order of magnitude.
Before discussing these results further, consider Fig. 10c, which
shows the variations from the mean runtime for each of the times of Acknowledgments
flight. Observe that the variations are clustered around 0 ms and are This research was supported in part by Jet Propulsion Laboratory
uncorrelated with the mean runtimes in Fig. 10a and with feasibility. (JPL), California Institute of Technology, Contract No. 1492781. Part of
These independent, small variations from the mean show that no this research was performed at JPL, California Institute of Technology,
intermittent tasks were meaningfully interrupting the solver. Also, under a contract with the National Aeronautics and Space Administration.
because the magnitudes of the variations from the mean are <1%, the Parts of this research are funded by Office of Naval Research Grant
mean runtimes can accurately be referred to simply as “runtimes.” No. N00014-14-1-0314 and National Science Foundation Grant
In addition, over all of the 2500 PDG trajectory optimizations, the No. CNS-1619729. The authors thank Tim Canham of JPL, who
parser runtime averaged 2.1 ms per trajectory with variations of only supported the runtime characterization on a flight processor. We are
several microseconds. This repeatable runtime for the parser is grateful for our collaborators Lars Blackmore of SpaceX; John M.
expected because it only encodes data: its computations are not Carson, David S. Bayard, and Jordi Casoliva of JPL; Stephen Boyd of
affected by feasibility or infeasibility. Stanford University; Jacob Mattingley of Metamarkets; and Ping Lu of
Comparing Figs. 10a and 10b, it is clear (and expected) that, for Iowa State for their valuable comments and insights. We would also like to
feasible trajectories, runtime is effectively the number of iterations thank the anonymous reviewers, whose comments were very useful in
multiplied by the average time for an iteration. It is also expected that improving the quality of the paper.
more iterations are required to converge as the time of flight
approaches the feasibility boundary from the feasible side. To obtain
an average time per iteration, note that for times of flight larger than References
50 s, the number of iterations is 11 and the runtime is almost constant [1] Mendeck, G. F., and Craig, L. E., “Entry Guidance for the 2011 Mars
(there is a slight downward trend). Computing an average runtime per Science Laboratory Mission,” AIAA Atmospheric Flight Mechanics
iteration from these times-of-flight and multiplying by the number of Conference and Exhibit, AIAA Paper 2011-6639, 2011, pp. 8–11.
iterations produces the estimates shown in Fig. 10a. The two outliers doi:10.2514/6.2011-6639
in the estimates are an area for future investigation. [2] Steltzner, A., “Overview of the Mars Science Laboratory Entry,
Considering the left side of Fig. 10a, the time to determine Descent, and Landing System,” AIAA/AAS Spaceflight Mechanics
infeasibility is uncorrelated with number of iterations, which is not Meeting, AAS Paper AAS 13-236, Kauai, HI, 2013.
unexpected because each iteration can move to a significantly different [3] Way, D. W., Powell, R. W., Chen, A., Steltzner, A. D., San Martin, A. M.,
Burkhart, P. D., and Mendeck, G. F., “Mars Science Laboratory: Entry,
area of the solution domain. Moreover, it can take 50% longer to Descent, and Landing System Performance,” IEEE Aerospace
determine infeasibility than to calculate a barely-feasible trajectory. Conference, Inst. of Electrical and Electronics Engineers Paper
The noncustomized, general solver was also tested. All the AERO.2007.352821, March 2006, pp. 1–19.
characteristics displayed in Fig. 10 are identical for the general solver doi:10.1109/AERO.2007.352821
on a flight processor, except that the time to determine infeasibility is [4] Ploen, S., Açıkmeşe, B., and Wolf, A., “A Comparison of Powered
relatively constant at 1.55 s. More important, because the -O3 Descent Guidance Laws for Mars Pinpoint Landing,” AIAA GNC
compile flag could not be enforced in the current implementation of Conference and Exhibit, AIAA Paper 2006-6676, 2006.
the customized solver, customization gives only a 16% speed doi:10.2514/6.2006-6676
improvement over the general solver on this flight processor. A 50% [5] Eren, U., Dueri, D., and Açıkmeşe, B., “Constrained Reachability and
Controllability Sets for Planetary Precision Landing via Convex
improvement was obtained on a desktop processor. Optimization,” Journal of Guidance, Control, and Dynamics, Vol. 38,
Nonetheless, it has been shown that per time of flight, infeasibility No. 11, 2015, pp. 2067–2083.
or an optimal trajectory can be calculated in approximately 0.7 s (i.e., [6] Wolf, A. A., Tooley, J., Ploen, S., Ivanov, M., Acikmese, B., and
the average of all 2500 solver runtimes) on a state-of-the-art Gromov, K., “Performance Trades for Mars Pinpoint Landing,” IEEE
radiation-hardened flight processor. In practice, PDG would not have Aerospace Conference, Inst. of Electrical and Electronics Engineers
DUERI ET AL. 211

Paper AERO.2006.1655793, 2006, pp. 1–0. [27] Frick, D., Domahidi, A., and Morari, M., “Embedded Optimization for
doi:10.1109/AERO.2006.1655793 Mixed Logical Dynamical Systems,” Computers and Chemical
[7] Johnson, A., Montgomery, J., and Matthies, L., “Vision Guided Landing Engineering, Vol. 72, Jan. 2015, pp. 21–33, A Tribute to Ignacio E.
of an Autonomous Helicopter in Hazardous Terrain,” Proceedings of Grossmann.
IEEE International Conference on Robotics and Automation (ICRA), doi:10.1016/j.compchemeng.2014.06.005
IEEE Publ., Piscataway, NJ, 2005, pp. 3966–3971. [28] Açıkmeşe, B., Aung, M., Casoliva, J., Mohan, S., Johnson, A., Scharf,
doi:10.1109/ROBOT.2005.1570727 D., Masten, D., Scotkin, J., Wolf, A., and Regehr, M. W., “Flight Testing
[8] Açıkmeşe, B., and Ploen, S. R., “Convex Programming Approach to of Trajectories Computed by G-FOLD: Fuel Optimal Large Divert
Powered Descent Guidance for Mars Landing,” Journal of Guidance, Guidance Algorithm for Planetary Landing,” AAS/AIAA Spaceflight
Control and Dynamics, Vol. 30, No. 5, 2007, pp. 1353–1366. Mechanics Meeting, AAS Paper 13-386, 2013.
doi:10.2514/1.27553 [29] Scharf, D. P., Regehr, M. W., Dueri, D., Açıkmeşe, B., Vaughan, G. M.,
[9] Açıkmeşe, B., Carson, J., and Blackmore, L., “Lossless Convexification Benito, J., Ansari, H., Aung, M., Johnson, A., Masten, D., Nietfeld, S.,
of Non-Convex Control Bound and Pointing Constraints of the Soft Casoliva, J., and Mohan, S., “ADAPT Demonstrations of Onboard
Landing Optimal Control Problem,” IEEE Transactions on Control Large-Divert Guidance with a VTVL Rocket,” IEEE Aerospace
Systems Technology, Vol. 21, No. 6, 2013, pp. 2104–2113. Conference, Inst. of Electrical and Electronics Engineers Paper
doi:10.1109/TCST.2012.2237346 AERO.2014.6836462, 2014.
[10] Blackmore, L., Açıkmeşe, B., and Scharf, D. P., “Minimum Landing doi:10.1109/AERO.2014.6836462
Error Powered Descent Guidance for Mars Landing Using Convex [30] “JPL, Masten Space Systems, and University of Texas, First Flight
Optimization,” Journal of Guidance, Control and Dynamics, Vol. 33, Testing of Real-Time G-FOLD, Guidance for Fuel Optimal Large
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

No. 4, 2010, pp. 1161–1171. Divert, Validation,” 12 Aug. 2013, http://www.jpl.nasa.gov/news/news.


doi:10.2514/1.47202 php?release=2013-247.
[11] Liu, X., and Lu, P., “Solving Nonconvex Optimal Control Problems by [31] Scharf, D., Açikmeşe, B., Dueri, D., Casoliva, J., and Benito, J.,
Convex Optimization,” Journal of Guidance, Control, and Dynamics, “Implementation and Experimental Demonstration of Onboard
Vol. 37, No. 3, 2014, pp. 750–765. Powered Descent Guidance,” Journal of Guidance, Control, and
doi:10.2514/1.62110 Dynamics, 2015.
[12] Meditch, J. S., “On the Problem of Optimal Thrust Programming for a [32] Harris, M., and Açıkmeşe, B., “Lossless Convexification of Non-
Lunar Soft Landing,” IEEE Transactions on Automatic Control, Vol. 9, Convex Optimal Control Problems for State Constrained Linear
No. 4, 1964, pp. 477–484. Systems,” Automatica, Vol. 50, No. 9, 2014, pp. 2304–2311.
doi:10.1109/TAC.1964.1105758 doi:10.1016/j.automatica.2014.06.008
[13] Klumpp, A. R., “Apollo Lunar Descent Guidance,” Automatica, Vol. 10, [33] Pontryagin, L. S., Boltyanskii, V. G., Gamkrelidze, V. G., and
No. 2, 1974, pp. 133–146. Mischenko, E. F., The Mathematical Theory of Optimal Processes,
doi:10.1016/0005-1098(74)90019-3 Pergamon Press, Oxford, England, 1964.
[14] Najson, F., and Mease, K. D., “Computationally Inexpensive Guidance [34] Berkovitz, L. D., Optimal Control Theory, Springer–Verlag, New York,
Algorithm for Fuel-Efficient Terminal Descent,” Journal of Guidance, 1975.
Control, and Dynamics, Vol. 29, No. 4, 2006, pp. 955–964. [35] Milyutin, A., and Osmolovskii, N., Calculus of Variations and Optimal
doi:10.2514/1.17715 Control, American Mathematical Society, Providence, Rhode Island,
[15] Topcu, U., Casoliva, J., and Mease, K. D., “Minimum-Fuel Powered 1998.
Descent for Mars Pinpoint Landing,” Journal of Spacecraft and [36] JPL, Systems, M. S., and of Texas at Austin, U., “750 Meter Divert
Rockets, Vol. 44, No. 2, 2007, pp. 324–331. Xombie Test Flight for G-FOLD, Guidance for Fuel Optimal Large
doi:10.2514/1.25023 Divert, Validation,” Sept. 2013, http://www.jpl.nasa.gov/video/?
[16] Steinfeld, B. A., Grant, M. J., Matz, D. A., Braun, R. D., and Barton, G. id=1270 [retrieved April 2015].
H., “Guidance, Navigation and Control System Performance Trades for [37] Kim, Y., and Mesbahi, M., “Quadratically Constrained Attitude Control
Mars Pinpoint Landing,” Journal of Spacecraft and Rockets, Vol. 47, via Semidefinite Programming,” IEEE Transactions on Automatic
No. 1, 2010, pp. 188–198. Control, Vol. 49, No. 5, 2004, pp. 731–735.
doi:10.2514/1.45779 doi:10.1109/TAC.2004.825959
[17] Açıkmeşe, B., and Ploen, S. R., “A Powered Descent Guidance [38] Lee, U., and Mesbahi, M., “Constrained Consensus via Logarithmic
Algorithm for Mars Pinpoint Landing,” AIAA GNC Conference and Barrier Functions,” 50th IEEE Conference on Decision and Control
Exhibit, AIAA Paper 2005-6288, 2005. and European Control Conference (CDC-ECC), Inst. of Electrical and
doi:10.2514/6.2005-6288 Electronics Engineers Paper CDC.2011.6161496, 2011, pp. 3608–
[18] Blackmore, L., Açıkmeşe, B., and Carson, J. M., “Lossless 3613.
Convexification of Control Constraints for a Class of Nonlinear doi:10.1109/CDC.2011.6161496
Optimal Control Problems,” System and Control Letters, Vol. 61, No. 8, [39] Mehrotra, S., “On the Implementation of a Primal-Dual Interior Point
2012, pp. 863–870. Method,” SIAM Journal on Optimization, Vol. 2, No. 4, 1992, pp. 575–601.
doi:10.1016/j.sysconle.2012.04.010 doi:10.1137/0802028
[19] Harris, M. W., and Açıkmeşe, B., “Maximum Divert for Planetary [40] Mehrotra, S., and Sun, J., “A Method of Analytic Centers for
Landing Using Convex Optimization,” Journal of Optimization Theory Quadratically Constrained Convex Quadratic Programs,” SIAM Journal
and Applications, Vol. 162, No. 3, 2014, pp. 975–995. on Numerical Analysis, Vol. 28, No. 2, 1991, pp. 529–544.
[20] Nesterov, Y., and Nemirovsky, A., Interior-Point Polynomial Methods doi:10.1137/0728029
in Convex Programming, SIAM, Philadelphia, PA, 1994. [41] Karmarkar, N., “A New Polynomial-Time Algorithm for Linear
[21] Boyd, S., and Vandenberghe, L., Convex Optimization, Cambridge Programming,” Proceedings of the Sixteenth Annual ACM Symposium
Univ. Press, Cambridge, England, 2004. on Theory of Computing, ACM, New York, 1984, pp. 302–311.
[22] Peng, J., Roos, C., and Terlaky, T., Self-Regularity: A New Paradigm for doi:10.1145/800057.808695
Primal-Dual Interior-Point Algorithms, Princeton Series in Applied [42] Wright, S. J., Primal-Dual Interior-Point Methods, Vol. 54, Society for
Mathematics, Univ. Press, Princeton, NJ, 2001. Industrial and Applied Mathematics, Philadelphia, PA, 1997.
[23] Mattingley, J., and Boyd, S., “CVXGEN: A Code Generator for [43] Nocedal, J., and Wright, S. J., Numerical Optimization, edited by
Embedded Convex Optimization,” Optimization and Engineering, Mikosch, T. V., Robinson, S. M., and Resnick, S. I., Springer Series in
Vol. 13, No. 1, 2012, pp. 1–27. Operations Research, Springer, New York, 1999.
doi:10.1007/s11081-011-9176-9 [44] Wang, B., “Implementation of Interior Point Methods for Second Order
[24] Dueri, D., Zhang, J., and Açıkmeşe, B., “Automated Custom Code Conic Optimization,” Master’s Thesis, McMaster Univ., Hamilton, ON,
Generation for Embedded, Real-Time Second Order Cone Programming,” 2003.
IFAC World Congress, IFAC Paper 1003.02736, 2014, pp. 1605–1612. [45] Vandenberghe, L., “The CVXOPT Linear and Quadratic Cone Program
doi:10.3182/20140824-6-ZA-1003.02736 Solvers,” 2010, http://www.seas.ucla.edu/vandenbe.
[25] Mattingley, J., and Boyd, S., “Real-Time Convex Optimization in Signal [46] Nesterov, Y., and Nemirovski, A., Interior Point Polynomial Algorithms
Processing,” IEEE Signal Processing Magazine, Vol. 27, No. 3, 2010, in Convex Programming, Society for Industrial and Applied
pp. 50–61. Mathematics, Philadelphia, PA, 1994.
doi:10.1109/MSP.2010.936020 [47] Nesterov, Y. E., and Todd, M. J., “Self-Scaled Barriers and Interior-Point
[26] Domahidi, A., Chu, E., and Boyd, S., “ECOS: An SOCP Solver for Methods for Convex Programming,” Mathematics of Operations
Embedded Systems,” Proceedings European Control Conference, Inst. Research, Vol. 22, No. 1, Feb. 1997, pp. 1–42.
of Electrical and Electronics Paper 13936337, 2013, pp. 3071–3076. doi:10.1287/moor.22.1.1
212 DUERI ET AL.

[48] Hager, W. W., “Updating the Inverse of a Matrix,” SIAM Review, Vol. 31, Specialist Conference, AAS Paper 2008-6426, 2008.
No. 2, June 1989, pp. 221–239. doi:10.2514/6.2008-6426
doi:10.1137/1031049 [52] Tutuncu, R. H., Toh, K. C., and Todd, M. J., “Solving Semidefinite-
[49] Amestoy, P. R., Davis, T. A., and Duff, I. S., “Algorithm 837: AMD, An Quadratic-Linear Problems Using SDPT3,” Mathematical Program-
Approximate Minimum Degree Ordering Algorithm,” ACM Transactions ming, Vol. 95, No. 2, Feb. 2003, pp. 189–217.
on Mathematical Software, Vol. 30, No. 3, Sept. 2004, pp. 381–388. [53] Sturm, J., “Using SeDuMi 1.02, a MATLAB Toolbox for Optimization
doi:10.1145/1024074 over Symmetric Cones,” Optimization Methods and Software, Vols. 11–
[50] Açıkmeşe, B., and Blackmore, L., “Lossless Convexification for a Class 12, 1999, pp. 625–653, Ver. 1.05.
of Optimal Control Problems with Nonconvex Control Constraints,” [54] Scharf, D., Ploen, S., and Açikmeşe, B., “Interpolation-Enhanced
Automatica, Vol. 47, No. 2, 2011, pp. 341–347. Powered Descent Guidance for Onboard Nominal, Off-Nominal, and
doi:10.1016/j.automatica.2010.10.037 Multi-X Scenarios,” AIAA Guidance, Navigation, and Control
[51] Açıkmese, B., Blackmore, L., Scharf, D. P., and Wolf, A., Conference, AIAA Paper 2015-0850, 2015.
“Enhancements on the Convex Programming Based Powered Descent doi:10.2514/6.2015-0850
Guidance Algorithm for Mars Landing,” AIAA/AAS Astrodynamics
Downloaded by NASA JET PROPULSION LABORATORY on June 13, 2018 | http://arc.aiaa.org | DOI: 10.2514/1.G001480

You might also like