Skip to content

Commit 57345b6

Browse files
committed
fixes
1 parent 48ae626 commit 57345b6

File tree

15 files changed

+102
-102
lines changed

15 files changed

+102
-102
lines changed

README.md

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,8 @@ function particle(x, u, w)
4848
end
4949

5050
# model
51-
dyn = Dynamics(particle, num_state, num_action)
52-
model = [dyn for t = 1:T-1]
51+
dynamics = Dynamics(particle, num_state, num_action)
52+
model = [dynamics for t = 1:T-1]
5353

5454
# initialization
5555
x1 = [0.0; 0.0]
@@ -62,17 +62,17 @@ ot = (x, u, w) -> 0.1 * dot(x, x) + 0.1 * dot(u, u)
6262
oT = (x, u, w) -> 0.1 * dot(x, x)
6363
ct = Cost(ot, num_state, num_action)
6464
cT = Cost(oT, num_state, 0)
65-
obj = [[ct for t = 1:T-1]..., cT]
65+
objective = [[ct for t = 1:T-1]..., cT]
6666

6767
# constraints
6868
goal(x, u, w) = x - xT
6969

7070
cont = Constraint()
7171
conT = Constraint(goal, num_state, 0)
72-
cons = [[cont for t = 1:T-1]..., conT]
72+
constraints = [[cont for t = 1:T-1]..., conT]
7373

7474
# problem
75-
prob = Solver(model, obj, cons)
75+
prob = Solver(model, objective, constraints)
7676
initialize_controls!(prob, ū)
7777
initialize_states!(prob, x̄)
7878

examples/acrobot.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -89,8 +89,8 @@ function midpoint_explicit(x, u, w)
8989
end
9090

9191
# ## model
92-
dyn = Dynamics(midpoint_explicit, num_state, num_action, num_parameter)
93-
model = [dyn for t = 1:T-1]
92+
dynamics = Dynamics(midpoint_explicit, num_state, num_action, num_parameter)
93+
model = [dynamics for t = 1:T-1]
9494

9595
# ## initialization
9696
x1 = [0.0; 0.0; 0.0; 0.0]
@@ -104,17 +104,17 @@ ot = (x, u, w) -> 0.1 * dot(x[3:4], x[3:4]) + 0.1 * dot(u, u)
104104
oT = (x, u, w) -> 0.1 * dot(x[3:4], x[3:4])
105105
ct = Cost(ot, num_state, num_action, num_parameter)
106106
cT = Cost(oT, num_state, 0, num_parameter)
107-
obj = [[ct for t = 1:T-1]..., cT]
107+
objective = [[ct for t = 1:T-1]..., cT]
108108

109109
# ## constraints
110110
goal(x, u, w) = x - xT
111111

112112
cont = Constraint()
113113
conT = Constraint(goal, num_state, 0)
114-
cons = [[cont for t = 1:T-1]..., conT]
114+
constraints = [[cont for t = 1:T-1]..., conT]
115115

116116
# ## problem
117-
prob = Solver(model, obj, cons)
117+
prob = Solver(model, objective, constraints)
118118
initialize_controls!(prob, ū)
119119
initialize_states!(prob, x̄)
120120

examples/car.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@ function midpoint_explicit(x, u, w)
2626
end
2727

2828
# ## model
29-
dyn = Dynamics(midpoint_explicit, num_state, num_action, num_parameter)
30-
model = [dyn for t = 1:T-1]
29+
dynamics = Dynamics(midpoint_explicit, num_state, num_action, num_parameter)
30+
model = [dynamics for t = 1:T-1]
3131

3232
# ## initialization
3333
x1 = [0.0; 0.0; 0.0]
@@ -43,7 +43,7 @@ ot = (x, u, w) -> 1.0 * dot(x - xT, x - xT) + 1.0e-2 * dot(u, u)
4343
oT = (x, u, w) -> 1000.0 * dot(x - xT, x - xT)
4444
ct = Cost(ot, num_state, num_action, num_parameter)
4545
cT = Cost(oT, num_state, 0, num_parameter)
46-
obj = [[ct for t = 1:T-1]..., cT]
46+
objective = [[ct for t = 1:T-1]..., cT]
4747

4848
# ## constraints
4949
ul = -5.0 * ones(num_action)
@@ -71,10 +71,10 @@ end
7171

7272
cont = Constraint(stage_con, num_state, num_action, indices_inequality=collect(1:5))
7373
conT = Constraint(terminal_con, num_state, num_action, indices_inequality=collect(3 .+ (1:1)))
74-
cons = [[cont for t = 1:T-1]..., conT]
74+
constraints = [[cont for t = 1:T-1]..., conT]
7575

7676
# ## problem
77-
prob = Solver(model, obj, cons)
77+
prob = Solver(model, objective, constraints)
7878
initialize_controls!(prob, ū)
7979
initialize_states!(prob, x̄)
8080

examples/particle.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,8 @@ function particle(x, u, w)
2121
end
2222

2323
# ## model
24-
dyn = Dynamics(particle, num_state, num_action)
25-
model = [dyn for t = 1:T-1]
24+
dynamics = Dynamics(particle, num_state, num_action)
25+
model = [dynamics for t = 1:T-1]
2626

2727
# ## initialization
2828
x1 = [0.0; 0.0]
@@ -35,17 +35,17 @@ ot = (x, u, w) -> 0.1 * dot(x, x) + 0.1 * dot(u, u)
3535
oT = (x, u, w) -> 0.1 * dot(x, x)
3636
ct = Cost(ot, num_state, num_action)
3737
cT = Cost(oT, num_state, 0)
38-
obj = [[ct for t = 1:T-1]..., cT]
38+
objective = [[ct for t = 1:T-1]..., cT]
3939

4040
# ## constraints
4141
goal(x, u, w) = x - xT
4242

4343
cont = Constraint()
4444
conT = Constraint(goal, num_state, 0)
45-
cons = [[cont for t = 1:T-1]..., conT]
45+
constraints = [[cont for t = 1:T-1]..., conT]
4646

4747
# ## problem
48-
prob = Solver(model, obj, cons)
48+
prob = Solver(model, objective, constraints)
4949
initialize_controls!(prob, ū)
5050
initialize_states!(prob, x̄)
5151

src/augmented_lagrangian.jl

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -36,25 +36,25 @@ function augmented_lagrangian(model::Model{T}, costs::Objective{T}, constraints:
3636
constraint_jacobian_action_tmp)
3737
end
3838

39-
function cost(obj::AugmentedLagrangianCosts, states, actions, parameters)
39+
function cost(objective::AugmentedLagrangianCosts, states, actions, parameters)
4040
# costs
41-
J = cost(obj.costs, states, actions, parameters)
41+
J = cost(objective.costs, states, actions, parameters)
4242

4343
# constraints
44-
c = obj.constraint_data.violations
45-
ρ = obj.constraint_penalty
46-
λ = obj.constraint_dual
47-
a = obj.active_set
44+
c = objective.constraint_data.violations
45+
ρ = objective.constraint_penalty
46+
λ = objective.constraint_dual
47+
a = objective.active_set
4848

4949
# horizon
5050
H = length(c)
5151

52-
constraint!(obj.constraint_data, states, actions, parameters)
53-
active_set!(a, obj.constraint_data, λ)
52+
constraint!(objective.constraint_data, states, actions, parameters)
53+
active_set!(a, objective.constraint_data, λ)
5454

5555
for t = 1:H
5656
J += λ[t]' * c[t]
57-
num_constraint = obj.constraint_data.constraints[t].num_constraint
57+
num_constraint = objective.constraint_data.constraints[t].num_constraint
5858
for i = 1:num_constraint
5959
if a[t][i] == 1
6060
J += 0.5 * ρ[t][i] * c[t][i]^2.0
@@ -84,29 +84,29 @@ function active_set!(a, data::ConstraintsData, λ)
8484
end
8585
end
8686

87-
function augmented_lagrangian_update!(obj::AugmentedLagrangianCosts;
87+
function augmented_lagrangian_update!(objective::AugmentedLagrangianCosts;
8888
scaling_penalty=10.0,
8989
max_penalty=1.0e12)
9090

9191
# constraints
92-
c = obj.constraint_data.violations
93-
cons = obj.constraint_data.constraints
94-
ρ = obj.constraint_penalty
95-
λ = obj.constraint_dual
92+
c = objective.constraint_data.violations
93+
constraints = objective.constraint_data.constraints
94+
ρ = objective.constraint_penalty
95+
λ = objective.constraint_dual
9696

9797
# horizon
9898
H = length(c)
9999

100100
for t = 1:H
101-
num_constraint = cons[t].num_constraint
101+
num_constraint = constraints[t].num_constraint
102102
for i = 1:num_constraint
103103
λ[t][i] += ρ[t][i] * c[t][i]
104-
if i in cons[t].indices_inequality
104+
if i in constraints[t].indices_inequality
105105
λ[t][i] = max(0.0, λ[t][i])
106106
end
107107
ρ[t][i] = min(scaling_penalty * ρ[t][i], max_penalty)
108108
end
109109
end
110110
end
111111

112-
Base.length(obj::AugmentedLagrangianCosts) = length(obj.costs)
112+
Base.length(objective::AugmentedLagrangianCosts) = length(objective.costs)

src/data/constraints.jl

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,12 @@ struct ConstraintsData{T,C,CX,CU}
88
jacobian_action::Vector{CU}
99
end
1010

11-
function constraint_data(model::Model, cons::Constraints)
12-
H = length(cons)
13-
c = [zeros(cons[t].num_constraint) for t = 1:H]
14-
cx = [zeros(cons[t].num_constraint, t < H ? model[t].num_state : model[H-1].num_next_state) for t = 1:H]
15-
cu = [zeros(cons[t].num_constraint, model[t].num_action) for t = 1:H-1]
16-
ConstraintsData(cons, c, cx, cu)
11+
function constraint_data(model::Model, constraints::Constraints)
12+
H = length(constraints)
13+
c = [zeros(constraints[t].num_constraint) for t = 1:H]
14+
cx = [zeros(constraints[t].num_constraint, t < H ? model[t].num_state : model[H-1].num_next_state) for t = 1:H]
15+
cu = [zeros(constraints[t].num_constraint, model[t].num_action) for t = 1:H-1]
16+
ConstraintsData(constraints, c, cx, cu)
1717
end
1818

1919
function constraint!(constraint_data::ConstraintsData, x, u, w)

src/data/solver.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ end
6161
# TODO: fix iter
6262
function cache!(data::SolverData)
6363
iter = 1 #data.cache[:iter]
64-
# (iter > length(data[:obj])) && (@warn "solver data cache exceeded")
64+
# (iter > length(data[:objective])) && (@warn "solver data cache exceeded")
6565
data.cache[:objective][iter] = data.objective[1]
6666
data.cache[:gradient][iter] = data.gradient
6767
data.cache[:max_violation][iter] = data.max_violation

src/gradients.jl

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ function gradients!(dynamics::Model, data::ProblemData;
77
jacobian!(jx, ju, dynamics, x, u, w)
88
end
99

10-
function gradients!(obj::Objective, data::ProblemData;
10+
function gradients!(objective::Objective, data::ProblemData;
1111
mode=:nominal)
1212
x, u, w = trajectories(data,
1313
mode=mode)
@@ -16,11 +16,11 @@ function gradients!(obj::Objective, data::ProblemData;
1616
gxx = data.objective.hessian_state_state
1717
guu = data.objective.hessian_action_action
1818
gux = data.objective.hessian_action_state
19-
cost_gradient!(gx, gu, obj, x, u, w)
20-
cost_hessian!(gxx, guu, gux, obj, x, u, w)
19+
cost_gradient!(gx, gu, objective, x, u, w)
20+
cost_hessian!(gxx, guu, gux, objective, x, u, w)
2121
end
2222

23-
function gradients!(obj::AugmentedLagrangianCosts, data::ProblemData;
23+
function gradients!(objective::AugmentedLagrangianCosts, data::ProblemData;
2424
mode=:nominal)
2525
# objective
2626
gx = data.objective.gradient_state
@@ -30,29 +30,29 @@ function gradients!(obj::AugmentedLagrangianCosts, data::ProblemData;
3030
gux = data.objective.hessian_action_state
3131

3232
# constraints
33-
cons = obj.constraint_data.constraints
34-
c = obj.constraint_data.violations
35-
cx = obj.constraint_data.jacobian_state
36-
cu = obj.constraint_data.jacobian_action
37-
ρ = obj.constraint_penalty
38-
λ = obj.constraint_dual
39-
a = obj.active_set
40-
= obj.constraint_penalty_matrix
41-
c_tmp = obj.constraint_tmp
42-
cx_tmp = obj.constraint_jacobian_state_tmp
43-
cu_tmp = obj.constraint_jacobian_action_tmp
33+
constraints = objective.constraint_data.constraints
34+
c = objective.constraint_data.violations
35+
cx = objective.constraint_data.jacobian_state
36+
cu = objective.constraint_data.jacobian_action
37+
ρ = objective.constraint_penalty
38+
λ = objective.constraint_dual
39+
a = objective.active_set
40+
= objective.constraint_penalty_matrix
41+
c_tmp = objective.constraint_tmp
42+
cx_tmp = objective.constraint_jacobian_state_tmp
43+
cu_tmp = objective.constraint_jacobian_action_tmp
4444

4545
# horizon
46-
H = length(obj)
46+
H = length(objective)
4747

4848
# derivatives
49-
gradients!(obj.costs, data,
49+
gradients!(objective.costs, data,
5050
mode=mode)
51-
gradients!(obj.constraint_data, data,
51+
gradients!(objective.constraint_data, data,
5252
mode=mode)
5353

5454
for t = 1:H
55-
num_constraint = cons[t].num_constraint
55+
num_constraint = constraints[t].num_constraint
5656
for i = 1:num_constraint
5757
Iρ[t][i, i] = ρ[t][i] * a[t][i]
5858
end

src/solver.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,15 +8,15 @@ mutable struct Solver{T,N,M,NN,MM,MN,NNN,MNN,X,U,D,O,FX,FU,FW,OX,OU,OXX,OUU,OUX}
88
options::Options{T}
99
end
1010

11-
function Solver(dynamics::Vector{Dynamics{T}}, obj::Objective{T};
11+
function Solver(dynamics::Vector{Dynamics{T}}, objective::Objective{T};
1212
parameters=[[zeros(d.num_parameter) for d in dynamics]..., zeros(0)],
1313
options=Options{T}()) where T
1414

1515
# allocate policy data
1616
policy = policy_data(dynamics)
1717

1818
# allocate problem data
19-
problem = problem_data(dynamics, obj,
19+
problem = problem_data(dynamics, objective,
2020
parameters=parameters)
2121

2222
# allocate solver data

test/acrobot.jl

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -80,8 +80,8 @@
8080
end
8181

8282
# ## model
83-
dyn = Dynamics(midpoint_explicit, num_state, num_action, num_parameter=num_parameter)
84-
model = [dyn for t = 1:T-1]
83+
dynamics = Dynamics(midpoint_explicit, num_state, num_action, num_parameter=num_parameter)
84+
model = [dynamics for t = 1:T-1]
8585

8686
# ## initialization
8787
x1 = [0.0; 0.0; 0.0; 0.0]
@@ -95,14 +95,14 @@
9595
oT = (x, u, w) -> 0.1 * dot(x[3:4], x[3:4])
9696
ct = Cost(ot, num_state, num_action, num_parameter=num_parameter)
9797
cT = Cost(oT, num_state, 0, num_parameter=num_parameter)
98-
obj = [[ct for t = 1:T-1]..., cT]
98+
objective = [[ct for t = 1:T-1]..., cT]
9999

100100
# ## constraints
101101
goal(x, u, w) = x - xT
102102

103103
cont = Constraint()
104104
conT = Constraint(goal, num_state, 0)
105-
cons = [[cont for t = 1:T-1]..., conT]
105+
constraints = [[cont for t = 1:T-1]..., conT]
106106

107107
# ## problem
108108
options = Options(verbose=false,
@@ -115,7 +115,7 @@
115115
initial_constraint_penalty=1.0,
116116
scaling_penalty=10.0)
117117

118-
s = Solver(model, obj, cons, options=options)
118+
s = Solver(model, objective, constraints, options=options)
119119

120120
initialize_controls!(s, ū)
121121
initialize_states!(s, x̄)

test/benchmark.jl

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,13 @@ rollout!(prob.policy, prob.problem, step_size=prob.solver_data.step_size[1])
2929
@benchmark rollout!($prob.policy, $prob.problem, step_size=$prob.solver_data.step_size[1])
3030
@code_warntype rollout!(prob.policy, prob.problem, step_size=prob.solver_data.step_size[1])
3131

32-
augmented_lagrangian_update!(prob.problem.obj)
33-
@benchmark augmented_lagrangian_update!($prob.problem.obj)
34-
@code_warntype augmented_lagrangian_update!(prob.problem.obj)
32+
augmented_lagrangian_update!(prob.problem.objective)
33+
@benchmark augmented_lagrangian_update!($prob.problem.objective)
34+
@code_warntype augmented_lagrangian_update!(prob.problem.objective)
3535

36-
constraint_violation(prob.problem.obj.constraint_data)
37-
@benchmark constraint_violation($prob.problem.obj.constraint_data)
38-
@code_warntype constraint_violation(prob.problem.obj.constraint_data)
36+
constraint_violation(prob.problem.objective.constraint_data)
37+
@benchmark constraint_violation($prob.problem.objective.constraint_data)
38+
@code_warntype constraint_violation(prob.problem.objective.constraint_data)
3939

4040
initialize_controls!(prob, ū)
4141
@benchmark initialize_controls!($prob, $ū)
@@ -66,7 +66,7 @@ using BenchmarkTools
6666
@benchmark $A .= $(Diagonal(b .* a))
6767

6868
t = 1
69-
a = prob.problem.obj.constraint_penalty[t]
70-
b = prob.problem.obj.a[t]
71-
c = prob.problem.obj.constraint_penalty_matrix[t]
69+
a = prob.problem.objective.constraint_penalty[t]
70+
b = prob.problem.objective.a[t]
71+
c = prob.problem.objective.constraint_penalty_matrix[t]
7272
@benchmark $c .= $(Diagonal(a .* b))

0 commit comments

Comments
 (0)