Skip to content

Commit f556de4

Browse files
authored
Merge pull request #60 from RoboticExplorationLab/cones
Equality Cones
2 parents 99816ef + 0f98ce1 commit f556de4

26 files changed

+296
-207
lines changed

NEWS.md

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,12 @@
11
# New `v0.6`
2+
3+
## v`0.6.2`
4+
Treats equality constraints as cones.
5+
Fixes deprecation warnings and small API changes from RobotDynamics v`0.4.3`, including:
6+
- Replacing `Traj` with `SampledTrajectory`
7+
- Using `RobotDynamics.dims` instead of `Base.size`
8+
- Using `RobotDynamics.errstate_jacobian!` instead of `RobotDynamics.state_diff_jacobian!`
9+
210
## Updated to new RobotDynamics `v0.4` API
311
Allows for both inplace and out-of-place dynamics, cost, and constraint evaluations.
412
Jacobians can be calculated using finite differences, forward AD, or user-specified.

Project.toml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
name = "TrajectoryOptimization"
22
uuid = "c79d492b-0548-5874-b488-5a62c1d9d0ca"
3-
version = "0.6.1"
3+
version = "0.6.2"
44

55
[deps]
66
DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae"
@@ -20,7 +20,7 @@ DocStringExtensions = "0.8"
2020
FiniteDiff = "2"
2121
ForwardDiff = "0.10"
2222
MathOptInterface = "0.9"
23-
RobotDynamics = "0.4"
23+
RobotDynamics = "0.4.3"
2424
RobotZoo = "0.3"
2525
Rotations = "~1.0"
2626
StaticArrays = "1"

docs/src/constraint_interface.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -81,13 +81,13 @@ end
8181
control_dim(con::ControlNorm2) = con.m
8282
sense(::ControlNorm2) = Inequality()
8383
Base.length(::ControlNorm2) = 1
84-
function evaluate!(vals, con::ControlNorm2, Z::AbstractTrajectory, inds=1:length(Z))
84+
function evaluate!(vals, con::ControlNorm2, Z::SampledTrajectory, inds=1:length(Z))
8585
for (i,k) in enumerate(inds)
8686
u = control(Z[k])
8787
vals[i] = SA[norm(u) - con.a[i]]
8888
end
8989
end
90-
function jacobian!(∇c, con::ControlNorm2, Z::AbstractTrajectory, inds=1:length(Z),
90+
function jacobian!(∇c, con::ControlNorm2, Z::SampledTrajectory, inds=1:length(Z),
9191
is_const = BitArray(undef, size(∇c)))
9292
for (i,k) in enumerate(inds)
9393
u = control(Z[k])

docs/src/creating_problems.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -123,5 +123,5 @@ set_times!(Z::Traj, t::Vector)
123123

124124
To initialize a problem with a given `Traj` type, you can use
125125
```
126-
initial_trajectory!(::Problem, Z::AbstractTrajectory)
126+
initial_trajectory!(::Problem, Z::SampledTrajectory)
127127
```

src/TrajectoryOptimization.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ using RobotDynamics: AbstractModel, DiscreteDynamics, LieGroupModel, DiscreteLie
2424
QuadratureRule, Implicit, Explicit,
2525
state_dim, control_dim, output_dim,
2626
is_terminal, state_diff, state_diff_jacobian!,
27-
state, control, states, controls, gettimes, Traj, AbstractTrajectory,
27+
state, control, states, controls, gettimes, SampledTrajectory,
2828
num_vars, dims,
2929
FunctionSignature, DiffMethod,
3030
FiniteDifference, ForwardAD, StaticReturn, InPlace, UserDefined

src/abstract_constraint.jl

Lines changed: 28 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,20 @@ in, they are assumed to be consistent with those returned by `state_dim` and `co
158158
############################################################################################
159159
# EVALUATION METHODS #
160160
############################################################################################
161+
function evaluate_constraint!(::StaticReturn, con::AbstractConstraint, val, args...)
162+
val .= RD.evaluate(con, args...)
163+
end
164+
165+
function evaluate_constraint!(::InPlace, con::AbstractConstraint, val, args...)
166+
RD.evaluate!(con, val, args...)
167+
val
168+
end
169+
170+
function constraint_jacobian!(sig::FunctionSignature, diff::DiffMethod, con, jac, val, args...)
171+
RD.jacobian!(sig, diff, con, jac, val, args...)
172+
end
173+
174+
161175
"""
162176
evaluate!(vals, con::AbstractConstraint, Z, [inds])
163177
@@ -168,11 +182,11 @@ The `inds` argument determines at which knot points the constraint is evaluated.
168182
If `con` is a `StageConstraint`, this will call `evaluate(con, z)` by default, or
169183
`evaluate(con, z1, z2)` if `con` is a `CoupledConstraint`.
170184
"""
171-
@generated function RD.evaluate!(
185+
@generated function evaluate_constraints!(
172186
sig::StaticReturn,
173187
con::StageConstraint,
174188
vals::Vector{V},
175-
Z::AbstractTrajectory,
189+
Z::SampledTrajectory,
176190
inds = 1:length(Z)
177191
) where V
178192
op = V <: SVector ? :(=) : :(.=)
@@ -183,11 +197,11 @@ If `con` is a `StageConstraint`, this will call `evaluate(con, z)` by default, o
183197
end
184198
end
185199

186-
function RD.evaluate!(
200+
function evaluate_constraints!(
187201
sig::InPlace,
188202
con::StageConstraint,
189203
vals::Vector{<:AbstractVector},
190-
Z::AbstractTrajectory,
204+
Z::SampledTrajectory,
191205
inds = 1:length(Z)
192206
)
193207
for (i, k) in enumerate(inds)
@@ -198,7 +212,7 @@ end
198212
# function evaluate!(
199213
# vals::Vector{<:AbstractVector},
200214
# con::StageConstraint,
201-
# Z::AbstractTrajectory,
215+
# Z::SampledTrajectory,
202216
# inds = 1:length(Z),
203217
# )
204218
# for (i, k) in enumerate(inds)
@@ -209,7 +223,7 @@ end
209223
# function evaluate!(
210224
# vals::Vector{<:AbstractVector},
211225
# con::CoupledConstraint,
212-
# Z::AbstractTrajectory,
226+
# Z::SampledTrajectory,
213227
# inds = 1:length(Z)-1,
214228
# )
215229
# for (i, k) in enumerate(inds)
@@ -233,13 +247,13 @@ The values are stored in `∇c`, which should be a matrix of matrices. If `con`
233247
If `con` is a `StageConstraint`, this will call `jacobian!(∇c, con, z)` by default, or
234248
`jacobian!(∇c, con, z1, z2, i)` if `con` is a `CoupledConstraint`.
235249
"""
236-
function RD.jacobian!(
250+
function constraint_jacobians!(
237251
sig::FunctionSignature,
238252
dif::DiffMethod,
239253
con::StageConstraint,
240254
∇c::VecOrMat{<:AbstractMatrix},
241255
c::VecOrMat{<:AbstractVector},
242-
Z::AbstractTrajectory,
256+
Z::SampledTrajectory,
243257
inds = 1:length(Z)
244258
)
245259
for (i, k) in enumerate(inds)
@@ -250,7 +264,7 @@ end
250264
# function jacobian!(
251265
# ∇c::VecOrMat{<:AbstractMatrix},
252266
# con::StageConstraint,
253-
# Z::AbstractTrajectory,
267+
# Z::SampledTrajectory,
254268
# inds = 1:length(Z),
255269
# is_const = BitArray(undef, size(∇c))
256270
# )
@@ -262,7 +276,7 @@ end
262276
# function jacobian!(
263277
# ∇c::VecOrMat{<:AbstractMatrix},
264278
# con::CoupledConstraint,
265-
# Z::AbstractTrajectory,
279+
# Z::SampledTrajectory,
266280
# inds = 1:size(∇c, 1),
267281
# is_const = BitArray(undef, size(∇c))
268282
# )
@@ -295,7 +309,7 @@ function RD.∇jacobian!(
295309
H::VecOrMat{<:AbstractMatrix},
296310
λ::VecOrMat{<:AbstractVector},
297311
c::VecOrMat{<:AbstractVector},
298-
Z::AbstractTrajectory,
312+
Z::SampledTrajectory,
299313
inds = 1:length(Z)
300314
)
301315
for (i, k) in enumerate(inds)
@@ -305,7 +319,7 @@ end
305319

306320
function error_expansion!(jac, jac0, con::StageConstraint, model::DiscreteDynamics, G, inds) where C
307321
if jac !== jac0
308-
n,m = size(model)
322+
n,m = RD.dims(model)
309323
= RD.errstate_dim(model)
310324
ix = 1:
311325
iu =.+ (1:m)
@@ -329,7 +343,7 @@ end
329343
# function ∇jacobian!(
330344
# G::VecOrMat{<:AbstractMatrix},
331345
# con::StageConstraint,
332-
# Z::AbstractTrajectory,
346+
# Z::SampledTrajectory,
333347
# λ::Vector{<:AbstractVector},
334348
# inds = 1:length(Z),
335349
# is_const = ones(Bool, length(inds)),
@@ -345,7 +359,7 @@ end
345359
# function ∇jacobian!(
346360
# G::VecOrMat{<:AbstractMatrix},
347361
# con::CoupledConstraint,
348-
# Z::AbstractTrajectory,
362+
# Z::SampledTrajectory,
349363
# λ::Vector{<:AbstractVector},
350364
# inds = 1:length(Z),
351365
# is_const = ones(Bool, length(inds)),

src/cones.jl

Lines changed: 30 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,15 @@ If `sense(con) <: Conic` (i.e. not `Equality`), then the following operations ar
1313
abstract type ConstraintSense end
1414
abstract type Conic <: ConstraintSense end
1515

16+
struct IdentityCone <: Conic end
17+
struct ZeroCone <: Conic end
18+
1619
"""
1720
Equality constraints of the form ``g(x) = 0`.
1821
Type singleton, so it is created with `Equality()`.
1922
"""
20-
struct Equality <: ConstraintSense end
23+
const Equality = ZeroCone
24+
2125
"""
2226
Inequality constraints of the form ``h(x) \\leq 0``.
2327
Type singleton, so it is created with `Inequality()`.
@@ -37,10 +41,16 @@ the last element in the vector.
3741
"""
3842
struct SecondOrderCone <: Conic end
3943

44+
conename(::C) where {C <: Conic} = C.name.name
45+
46+
dualcone(::IdentityCone) = ZeroCone()
47+
dualcone(::ZeroCone) = IdentityCone()
4048
dualcone(::NegativeOrthant) = NegativeOrthant()
4149
dualcone(::PositiveOrthant) = PositiveOrthant()
4250
dualcone(::SecondOrderCone) = SecondOrderCone()
4351

52+
projection(::IdentityCone, x) = x
53+
projection(::ZeroCone, x) = zero(x)
4454
projection(::NegativeOrthant, x) = min.(0, x)
4555
projection(::PositiveOrthant, x) = max.(0, x)
4656

@@ -64,7 +74,9 @@ projection(::PositiveOrthant, x) = max.(0, x)
6474
end
6575
end
6676

67-
projection!(::Equality, px, x) = px .= 0
77+
projection!(::IdentityCone, px, x) = px .= x
78+
projection!(::ZeroCone, px, x) = px .= 0
79+
# projection!(::Equality, px, x) = px .= 0
6880

6981
function projection!(::NegativeOrthant, px, x)
7082
@assert length(px) == length(x)
@@ -95,6 +107,17 @@ function projection!(::SecondOrderCone, px, x::V) where V <: AbstractVector
95107
return pv
96108
end
97109

110+
function ∇projection!(::IdentityCone, J, x)
111+
T = eltype(J)
112+
J .= 0
113+
for i = 1:length(x)
114+
J[i,i] = one(T)
115+
end
116+
return J
117+
end
118+
119+
∇projection!(::ZeroCone, J, x) = J .= 0
120+
98121
function ∇projection!(::NegativeOrthant, J, x)
99122
for i in eachindex(x)
100123
J[i,i] = x[i] <= 0 ? 1 : 0
@@ -145,6 +168,8 @@ end
145168
end
146169
end
147170

171+
Base.in(x, ::IdentityCone) = true
172+
Base.in(x, ::ZeroCone) = norm(x, 1) zero(eltype(X))
148173
Base.in(x, ::NegativeOrthant) = all(x->x<=0, x)
149174

150175
function Base.in(x, ::SecondOrderCone)
@@ -154,6 +179,9 @@ function Base.in(x, ::SecondOrderCone)
154179
return a <= s
155180
end
156181

182+
∇²projection!(::IdentityCone, hess, x, b) = hess .= 0
183+
∇²projection!(::ZeroCone, hess, x, b) = hess .= 0
184+
157185
function ∇²projection!(::NegativeOrthant, hess, x, b)
158186
get_data(hess) .= 0
159187
end

src/conset.jl

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -23,19 +23,19 @@ Base.IteratorEltype(::AbstractConstraintSet) = Base.HasEltype()
2323
Base.eltype(::AbstractConstraintSet) = AbstractConstraint
2424

2525
# Constraint Evaluation
26-
function RD.evaluate!(conSet::AbstractConstraintSet, Z::AbstractTrajectory)
26+
function RD.evaluate!(conSet::AbstractConstraintSet, Z::SampledTrajectory)
2727
for i = 1:length(conSet)
2828
RD.evaluate!(conSet.convals[i], Z)
2929
end
3030
end
3131

32-
function RD.jacobian!(conSet::AbstractConstraintSet, Z::AbstractTrajectory, init::Bool=true)
32+
function RD.jacobian!(conSet::AbstractConstraintSet, Z::SampledTrajectory, init::Bool=true)
3333
for conval in get_convals(conSet)
3434
RD.jacobian!(conval, Z)
3535
end
3636
end
3737

38-
function RD.∇jacobian!(G::Vector{<:Matrix}, conSet::AbstractConstraintSet, Z::AbstractTrajectory,
38+
function RD.∇jacobian!(G::Vector{<:Matrix}, conSet::AbstractConstraintSet, Z::SampledTrajectory,
3939
λ::Vector{<:Vector})
4040
for (i,conval) in enumerate(get_convals(conSet))
4141
RD.∇jacobian!(G[i], conval, Z, λ[i])
@@ -102,7 +102,7 @@ function norm_violation!(conSet::AbstractConstraintSet, p=2)
102102
end
103103
end
104104

105-
function norm_dgrad(conSet::AbstractConstraintSet, dx::AbstractTrajectory, p=1)
105+
function norm_dgrad(conSet::AbstractConstraintSet, dx::SampledTrajectory, p=1)
106106
convals = get_convals(conSet)
107107
T = eltype(conSet.c_max)
108108
for i in eachindex(convals)

0 commit comments

Comments
 (0)