Skip to content

Commit 2acbb85

Browse files
committed
solver options
1 parent 62d7579 commit 2acbb85

File tree

6 files changed

+47
-10
lines changed

6 files changed

+47
-10
lines changed

.gitignore

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,3 +22,6 @@ docs/site/
2222
# committed for packages, but should be committed for applications that require a static
2323
# environment.
2424
Manifest.toml
25+
26+
# Ipopt output
27+
output.txt

Project.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
name = "DirectTrajectoryOptimization"
22
uuid = "a9f42406-efe7-414c-8b71-df971cc98041"
33
authors = ["thowell <thowell@stanford.edu>"]
4-
version = "0.1.0"
4+
version = "0.1.1"
55

66
[deps]
77
IfElse = "615f187c-cbe4-4ef1-ba3b-2fcf58d6d173"

examples/acrobot/acrobot.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ cons = ConstraintSet([x_init, x_goal], [StageConstraint()])
102102

103103
# ## problem
104104
trajopt = TrajectoryOptimizationProblem(obj, model, cons)
105-
s = Solver(trajopt)
105+
s = Solver(trajopt, options=Options())
106106

107107
# ## initialize
108108
x_interpolation = linear_interpolation(x1, xT, T)

examples/car/car.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ cons = ConstraintSet([bnd1, bndt, bndT], [cont, conT])
6060

6161
# ## problem
6262
trajopt = TrajectoryOptimizationProblem(obj, model, cons)
63-
s = Solver(trajopt)
63+
s = Solver(trajopt, options=Options())
6464

6565
# ## initialize
6666
x_interpolation = linear_interpolation(x1, xT, T)

src/DirectTrajectoryOptimization.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ export Dynamics, DynamicsModel
2929
export TrajectoryOptimizationProblem
3030

3131
# solver
32-
export Solver, initialize!, solve!
32+
export Solver, Options, initialize!, solve!
3333

3434
# utils
3535
export linear_interpolation

src/solver.jl

Lines changed: 40 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,36 @@
1+
@with_kw mutable struct Options{T}
2+
# Ipopt settings: https://coin-or.github.io/Ipopt/OPTIONS.html#OPT_print_options_documentation
3+
tol::T = 1e-6
4+
s_max::T = 100.0
5+
max_iter::Int = 1000
6+
# max_wall_time = 300.0
7+
max_cpu_time = 300.0
8+
dual_inf_tol::T = 1.0
9+
constr_viol_tol::T = 1.0e-3
10+
compl_inf_tol::T = 1.0e-3
11+
acceptable_tol::T = 1.0e-6
12+
acceptable_iter::Int = 15
13+
acceptable_dual_inf_tol::T = 1.0e10
14+
acceptable_constr_viol_tol::T = 1.0e-2
15+
acceptable_compl_inf_tol::T = 1.0e-2
16+
acceptable_obj_change_tol::T = 1.0e-5
17+
diverging_iterates_tol::T = 1.0e8
18+
mu_target::T = 1.0e-4
19+
print_level::Int = 5
20+
output_file = joinpath(dirname(pathof(DirectTrajectoryOptimization)), "..", "output.txt")
21+
print_user_options = "no"
22+
# print_options_documentation = "no"
23+
# print_timing_statistics = "no"
24+
print_options_mode = "text"
25+
# print_advanced_options = "no"
26+
print_info_string = "no"
27+
inf_pr_output = "original"
28+
print_frequency_iter = 1
29+
print_frequency_time = 0.0
30+
skip_finalize_solution_call = "no"
31+
# timing_statistics = :no
32+
end
33+
134
struct Solver{T}
235
p::Problem{T}
336
nlp_bounds::Vector{MOI.NLPBoundsPair}
@@ -6,18 +39,19 @@ struct Solver{T}
639
z::Vector{MOI.VariableIndex}
740
end
841

9-
function Solver(trajopt::TrajectoryOptimizationProblem; eval_hess=false, options=nothing)
42+
function Solver(trajopt::TrajectoryOptimizationProblem; eval_hess=false, options=Options())
1043
p = Problem(trajopt, eval_hess=eval_hess)
1144

1245
nlp_bounds = MOI.NLPBoundsPair.(p.con_bnds...)
1346
block_data = MOI.NLPBlockData(nlp_bounds, p, true)
1447

48+
# instantiate NLP solver
1549
solver = Ipopt.Optimizer()
16-
17-
# TODO: options
18-
solver.options["max_iter"] = 1000
19-
solver.options["tol"] = 1.0e-3
20-
solver.options["constr_viol_tol"] = 1.0e-3
50+
51+
# set NLP solver options
52+
for name in fieldnames(typeof(options))
53+
solver.options[String(name)] = getfield(options, name)
54+
end
2155

2256
z = MOI.add_variables(solver, p.num_var)
2357

0 commit comments

Comments
 (0)