Optimal control problem with free initial time
In this tutorial, we study a minimum-time optimal control problem with free initial time $t_0$ (negative). The goal is to determine the latest possible starting time so that the system reaches a fixed final state at $t_f = 0$.
The system is the classic double integrator:
- Initial state: $x(t_0)=[0,0]$, final state: $x(t_f)=[1,0]$
- Control bounds: $u(t) \in [-1,1]$
- Objective: maximize $t_0$ (equivalently minimize $-t_0$)
- Dynamics: $\dot{x}_1 = x_2, \ \dot{x}_2 = u$
using LinearAlgebra: norm
using OptimalControl
using NLPModelsIpopt
using NonlinearSolve
using OrdinaryDiffEq
using Plots
using PrintfProblem definition
We consider the following setup:
tf = 0 # Fixed final time
x0 = [0, 0] # Initial state
xf = [1, 0] # Final state
@def ocp begin
t0 ∈ R, variable # Free initial time
t ∈ [t0, tf], time
x ∈ R², state
u ∈ R, control
# Control bounds
-1 ≤ u(t) ≤ 1
# Boundary conditions
x(t0) == x0
x(tf) == xf
# Ensure t0 is negative and bounded for numerical stability
0.05 ≤ -t0 ≤ Inf
# Dynamics
ẋ(t) == [x₂(t), u(t)]
# Objective: maximize t0 (equivalent to minimizing -t0)
-t0 → min
endThis explicitly declares the free initial time via t0 ∈ R, variable and defines the time interval [t0, tf].
Direct solution
To improve convergence of the direct solver, we constrain t0 as follows:
-Inf ≤ t0 ≤ -0.05We solve the problem using a direct transcription method:
sol = solve(ocp; grid_size=100)▫ This is OptimalControl version v1.1.6 running with: direct, adnlp, ipopt.
▫ The optimal control problem is solved with CTDirect version v0.17.4.
┌─ The NLP is modelled with ADNLPModels and solved with NLPModelsIpopt.
│
├─ Number of time steps⋅: 100
└─ Discretisation scheme: midpoint
▫ This is Ipopt version 3.14.19, running with linear solver MUMPS 5.8.1.
Number of nonzeros in equality constraint Jacobian...: 904
Number of nonzeros in inequality constraint Jacobian.: 1
Number of nonzeros in Lagrangian Hessian.............: 201
Total number of variables............................: 303
variables with only lower bounds: 0
variables with lower and upper bounds: 100
variables with only upper bounds: 0
Total number of equality constraints.................: 204
Total number of inequality constraints...............: 1
inequality constraints with only lower bounds: 1
inequality constraints with lower and upper bounds: 0
inequality constraints with only upper bounds: 0
iter objective inf_pr inf_du lg(mu) ||d|| lg(rg) alpha_du alpha_pr ls
0 -1.0000000e-01 9.00e-01 1.11e-16 0.0 0.00e+00 - 0.00e+00 0.00e+00 0
1 1.0952350e-01 8.81e-01 8.86e+01 -6.0 1.06e+01 - 1.01e-03 2.10e-02h 3
2 3.1667808e-01 8.63e-01 6.81e+01 1.5 3.25e+01 - 1.74e-01 2.02e-02f 2
3 8.1075118e-01 8.21e-01 1.17e+03 0.5 1.34e+01 - 4.08e-02 4.92e-02f 2
4 1.0450133e+00 7.67e-01 9.75e+02 0.5 1.01e+01 - 1.40e-01 6.60e-02h 1
5 1.6383816e+00 5.94e-01 4.18e+02 0.7 5.11e+00 - 1.00e+00 2.25e-01h 1
6 2.9370638e+00 6.15e-03 2.81e+02 0.6 1.30e+00 - 9.78e-01 1.00e+00f 1
7 2.7272574e+00 1.79e-04 2.71e+01 -5.4 2.10e-01 - 9.35e-01 1.00e+00h 1
8 2.6456981e+00 4.75e-05 6.11e-01 -1.8 8.16e-02 0.0 9.99e-01 1.00e+00h 1
9 2.4141105e+00 5.10e-04 1.26e-01 -2.8 2.32e-01 - 9.99e-01 1.00e+00f 1
iter objective inf_pr inf_du lg(mu) ||d|| lg(rg) alpha_du alpha_pr ls
10 2.0359702e+00 1.78e-03 2.85e-02 -3.3 4.70e-01 - 9.96e-01 1.00e+00f 1
11 2.0150864e+00 1.32e-04 2.46e-03 -3.9 6.10e-01 - 9.92e-01 9.94e-01h 1
12 2.0048628e+00 7.92e-05 7.89e-04 -5.9 7.93e-01 - 7.13e-01 7.04e-01h 1
13 2.0002968e+00 3.74e-05 1.27e-05 -5.6 8.19e-01 - 1.00e+00 1.00e+00h 1
14 2.0000002e+00 6.33e-08 1.01e-07 -11.0 2.01e-02 - 9.90e-01 1.00e+00h 1
15 2.0000000e+00 3.17e-13 3.42e-14 -11.0 1.49e-04 - 1.00e+00 1.00e+00h 1
Number of Iterations....: 15
(scaled) (unscaled)
Objective...............: 1.9999999910019464e+00 1.9999999910019464e+00
Dual infeasibility......: 3.4194869158454821e-14 3.4194869158454821e-14
Constraint violation....: 3.1730174043786974e-13 3.1730174043786974e-13
Variable bound violation: 9.4974961228899701e-09 9.4974961228899701e-09
Complementarity.........: 1.5242398947043470e-11 1.5242398947043470e-11
Overall NLP error.......: 1.5242398947043470e-11 1.5242398947043470e-11
Number of objective function evaluations = 24
Number of objective gradient evaluations = 16
Number of equality constraint evaluations = 24
Number of inequality constraint evaluations = 24
Number of equality constraint Jacobian evaluations = 16
Number of inequality constraint Jacobian evaluations = 16
Number of Lagrangian Hessian evaluations = 15
Total seconds in IPOPT = 3.319
EXIT: Optimal Solution Found.The solution can be visualized:
plt = plot(sol; label="direct", size=(800, 600))Verification of the results
Using Pontryagin's Maximum Principle (PMP), the optimal control is bang-bang with a single switch at $t_1$:
\[u(t) = \begin{cases} 1, & t \in [t_0,t_1),\\ -1, & t \in [t_1,0]. \end{cases}\]
The corresponding trajectory, costate, switching time, and initial time are:
\[x_1(t) = \begin{cases} \tfrac{1}{2}(t-t_0)^2, & t \in [t_0,-1),\\ -\tfrac{1}{2}t^2 + 2 t_1 t - t_1^2 - t_0 t_1, & t \in [-1,0], \end{cases} \quad x_2(t) = \begin{cases} t - t_0, & t \in [t_0,-1),\\ 2 t_1 - t_0 - t, & t \in [-1,0], \end{cases}\]
\[p(t_0) = (1,1), \quad p(t_f) = (1,-1), \quad t_1=-1, \quad t_0=-2, \quad p^0=-1.\]
We can now compare the direct numerical solution with this theoretical result:
t0 = variable(sol)
u = control(sol)
p = costate(sol)
x = state(sol)
H(t) = p(t)[1]*x(t)[2] + p(t)[2]*u(t)
@printf("t0 = %.5f", t0); println(lpad("(expected -2)", 33))
@printf("H(t0) = %.5f", H(t0)); println(lpad("(expected 1)", 30))
@printf("H(tf) = %.5f", H(tf)); println(lpad("(expected 1)", 30))
@printf("x(t0) = [%.5f, %.5f]", x(t0)[1], x(t0)[2]); println(lpad("(expected [0, 0])", 23))
@printf("x(tf) = [%.5f, %.5f]", x(tf)[1], x(tf)[2]); println(lpad("(expected [1, 0])", 24))
@printf("p(t0) = [%.5f, %.5f]", p(t0)[1], p(t0)[2]); println(lpad("(expected [1, 1])", 24))
@printf("p(tf) = [%.5f, %.5f]", p(tf)[1], p(tf)[2]); println(lpad("(expected [1, -1])", 24))t0 = -2.00000 (expected -2)
H(t0) = 0.99666 (expected 1)
H(tf) = 1.00334 (expected 1)
x(t0) = [0.00000, 0.00000] (expected [0, 0])
x(tf) = [1.00000, 0.00000] (expected [1, 0])
p(t0) = [1.00000, 0.99666] (expected [1, 1])
p(tf) = [1.00000, -1.00334] (expected [1, -1])The numerical results match the theoretical solution almost exactly.
Indirect (shooting) solution
We now solve the PMP system numerically using an indirect method (shooting approach), using the direct solution as an initial guess.
# Pseudo-Hamiltonian
H(x, p, u) = p[1]*x[2] + p[2]*u
# Hamiltonian lift used to compute the switching function
F1(x) = [0, 1]
H1 = Lift(F1)Define the flows corresponding to the two control laws $u=+1$ and $u=-1$:
const u_pos = 1
const u_neg = -1
# Each flow depends on tf since it is part of the optimization variables
f_pos = Flow(ocp, (x, p, tf) -> u_pos)
f_neg = Flow(ocp, (x, p, tf) -> u_neg)The shooting function enforces:
- Continuity of state and costate
- Satisfaction of boundary conditions
- Switching condition ($p_2(t_1) = 0$)
- Hamiltonian normalization at initial time
function shoot!(s, p0, t1, t0)
x_t0 = x0
p_t0 = p0
# Forward under u = +1, then u = -1
x_t1, p_t1 = f_pos(t0, x_t0, p_t0, t1)
x_tf, p_tf = f_neg(t1, x_t1, p_t1, tf)
u_t0 = 1 # Initial control
# Shooting conditions:
s[1:2] = x_tf - xf # Terminal state match
s[3] = H(x_t0, p_t0, u_t0) - 1 # Hamiltonian normalization
s[4] = H1(x_t1, p_t1) # Switching condition φ(t₁)=0
endTo help the nonlinear solver converge, we build a good initial guess from the direct solution:
t = time_grid(sol)
x = state(sol)
p = costate(sol)
φ(t) = H1(x(t), p(t)) # Switching function
p0 = p(t[1])
t1 = t[argmin(abs.(φ.(t)))]
t0 = t[1]
println("t0 = ", t0)
println("p0 = ", p0)
println("t1 = ", t1)
# Evaluate the norm of the shooting function at initial guess
s = zeros(4)
shoot!(s, p0, t1, t0)
println("\n‖s‖ (initial guess) = ", norm(s), "\n")t0 = -1.9999999910019464
p0 = [0.9999999954958442, 0.9966602586258352]
t1 = -0.9999999955009732
‖s‖ (initial guess) = 0.0047231011799636555We can now solve the system using an indirect shooting method:
# Aggregated nonlinear system
shoot!(s, ξ, λ) = shoot!(s, ξ[1:2], ξ[3], ξ[4])
# Define the problem and initial guess
ξ_guess = [p0..., t1, t0]
prob = NonlinearProblem(shoot!, ξ_guess)
# Solve the nonlinear system
indirect_sol = solve(prob; show_trace=Val(true), abstol=1e-8, reltol=1e-8)
Algorithm: NewtonRaphson(
descent = NewtonDescent(),
autodiff = AutoForwardDiff(),
vjp_autodiff = AutoReverseDiff(
compile = false
),
jvp_autodiff = AutoForwardDiff(),
concrete_jac = Val{false}()
)
---- ------------- -----------
Iter f(u) inf-norm Step 2-norm
---- ------------- -----------
0 3.33974137e-03 0.00000000e+00
1 1.11022302e-16 3.33974137e-03
Final 1.11022302e-16
----------------------retcode: Success
u: 4-element Vector{Float64}:
1.0
1.0
-1.0000000000000002
-2.0000000000000004Compare indirect and direct solutions:
p0 = indirect_sol.u[1:2]
t1 = indirect_sol.u[3]
t0 = indirect_sol.u[4]
# Reconstruct the full trajectory
f = f_pos * (t1, f_neg)
flow_sol = f((t0, tf), x0, p0; saveat=range(t0, tf, 200))
# Plot comparison
plot!(plt, flow_sol; label="indirect", color=:red, linestyle=:dash)