Skip to content

Commit

Permalink
Swop parametric optim for manopt and better convolution performance (#…
Browse files Browse the repository at this point in the history
…1784)

* swop parametric optim for manopt

* improve non-parametric performance

* Standardise to use getManifold

* covariance calc try catch on hessian inverse
  • Loading branch information
Affie authored Oct 13, 2023
1 parent f1707b0 commit c49e4b0
Show file tree
Hide file tree
Showing 11 changed files with 94 additions and 68 deletions.
6 changes: 3 additions & 3 deletions benchmark/runbenchmarks.jl
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ fg.solverParams.graphinit=false;
addVariable!(fg, :x0, Pose2);
addFactor!(fg, [:x0], PriorPose2(MvNormal([0.0,0,0], diagm([0.1,0.1,0.01].^2))));

r = @timed IIF.solveGraphParametric!(fg; init=false);
r = @timed IIF.solveGraphParametric!(fg; init=false, is_sparse=false);

timed = [r];

Expand All @@ -44,7 +44,7 @@ for i = 1:14
to = Symbol("x",i)
addVariable!(fg, to, Pose2)
addFactor!(fg, [fr,to], Pose2Pose2(MvNormal([10.0,0,pi/3], diagm([0.5,0.5,0.05].^2))))
r = @timed IIF.solveGraphParametric!(fg; init=false);
r = @timed IIF.solveGraphParametric!(fg; init=false, is_sparse=false);
push!(timed, r)
end

Expand All @@ -53,7 +53,7 @@ addVariable!(fg, :l1, RoME.Point2, tags=[:LANDMARK;]);
addFactor!(fg, [:x0; :l1], Pose2Point2BearingRange(Normal(0.0,0.1), Normal(20.0, 1.0)));
addFactor!(fg, [:x6; :l1], Pose2Point2BearingRange(Normal(0.0,0.1), Normal(20.0, 1.0)));

r = @timed IIF.solveGraphParametric!(fg; init=false);
r = @timed IIF.solveGraphParametric!(fg; init=false, is_sparse=false);
push!(timed, r);

getproperty.(timed, :time)
Expand Down
4 changes: 2 additions & 2 deletions src/Factors/Circular.jl
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ DFG.getManifold(::CircularCircular) = RealCircleGroup()

function (cf::CalcFactor{<:CircularCircular})(X, p, q)
#
M = cf.manifold # getManifold(cf.factor)
M = getManifold(cf)
return distanceTangent2Point(M, X, p, q)
end

Expand Down Expand Up @@ -68,7 +68,7 @@ function getSample(cf::CalcFactor{<:PriorCircular})
end

function (cf::CalcFactor{<:PriorCircular})(m, p)
M = cf.manifold # getManifold(cf.factor)
M = getManifold(cf)
Xc = vee(M, p, log(M, p, m))
return Xc
end
Expand Down
2 changes: 1 addition & 1 deletion src/Factors/GenericFunctions.jl
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ DFG.getManifold(f::ManifoldPriorPartial) = f.M

function getSample(cf::CalcFactor{<:ManifoldPriorPartial})
Z = cf.factor.Z
M = cf.manifold # getManifold(cf.factor)
M = getManifold(cf)
partial = collect(cf.factor.partial)

return (samplePointPartial(M, Z, partial),)
Expand Down
4 changes: 2 additions & 2 deletions src/manifolds/services/ManifoldSampling.jl
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ See also: [`getMeasurementParametric`](@ref)
function getSample end

function getSample(cf::CalcFactor{<:AbstractPrior})
M = cf.manifold # getManifold(cf.factor)
M = getManifold(cf)
if hasfield(typeof(cf.factor), :Z)
X = samplePoint(M, cf.factor.Z)
else
Expand All @@ -132,7 +132,7 @@ function getSample(cf::CalcFactor{<:AbstractPrior})
end

function getSample(cf::CalcFactor{<:AbstractRelative})
M = cf.manifold # getManifold(cf.factor)
M =getManifold(cf)
if hasfield(typeof(cf.factor), :Z)
X = sampleTangent(M, cf.factor.Z)
else
Expand Down
2 changes: 1 addition & 1 deletion src/parametric/services/ParametricCSMFunctions.jl
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ function solveUp_ParametricStateMachine(csmc::CliqStateMachineContainer)
# store the cliqSubFg for later debugging
_dbgCSMSaveSubFG(csmc, "fg_beforeupsolve")

vardict, result, varIds, Σ = solveGraphParametric(csmc.cliqSubFg)
vardict, result, varIds, Σ = solveGraphParametricOptim(csmc.cliqSubFg)

logCSM(csmc, "$(csmc.cliq.id) vars $(keys(varIds))")
# @info "$(csmc.cliq.id) Σ $(Σ)"
Expand Down
44 changes: 33 additions & 11 deletions src/parametric/services/ParametricManopt.jl
Original file line number Diff line number Diff line change
Expand Up @@ -297,8 +297,13 @@ function covarianceFiniteDiff(M, jacF!::JacF_RLM!, p0)
H = FiniteDiff.finite_difference_hessian(costf, X0)

# inv(H)
Σ = Matrix(H) \ Matrix{eltype(H)}(I, size(H)...)
# sqrt.(diag(Σ))
Σ = try
Matrix(H) \ Matrix{eltype(H)}(I, size(H)...)
catch ex #TODO only catch correct exception and try with pinv as fallback in certain cases.
@warn "Hessian inverse failed" ex
# Σ = pinv(H)
nothing
end
return Σ
end

Expand Down Expand Up @@ -490,27 +495,28 @@ end
# new2 0.010764 seconds (34.61 k allocations: 3.111 MiB)
# dense J 0.022079 seconds (283.54 k allocations: 18.146 MiB)

function autoinitParametricManopt!(
function autoinitParametric!(
fg,
varorderIds = getInitOrderParametric(fg);
reinit = false,
kwargs...
)
@showprogress for vIdx in varorderIds
autoinitParametricManopt!(fg, vIdx; reinit, kwargs...)
autoinitParametric!(fg, vIdx; reinit, kwargs...)
end
return nothing
end

function autoinitParametricManopt!(dfg::AbstractDFG, initme::Symbol; kwargs...)
return autoinitParametricManopt!(dfg, getVariable(dfg, initme); kwargs...)
function autoinitParametric!(dfg::AbstractDFG, initme::Symbol; kwargs...)
return autoinitParametric!(dfg, getVariable(dfg, initme); kwargs...)
end

function autoinitParametricManopt!(
function autoinitParametric!(
dfg::AbstractDFG,
xi::DFGVariable;
solveKey = :parametric,
reinit::Bool = false,
perturb_point::Bool=false,
kwargs...,
)
#
Expand All @@ -528,12 +534,27 @@ function autoinitParametricManopt!(
return isInitialized(dfg, vl, solveKey)
end

vnd::VariableNodeData = getSolverData(xi, solveKey)

if perturb_point
_M = getManifold(xi)
p = vnd.val[1]
vnd.val[1] = exp(
_M,
p,
get_vector(
_M,
p,
randn(manifold_dimension(_M))*10^-6,
DefaultOrthogonalBasis()
)
)
end
M, vartypeslist, lm_r, Σ = solve_RLM_conditional(dfg, [initme], initfrom; kwargs...)

val = lm_r[1]
vnd::VariableNodeData = getSolverData(xi, solveKey)
vnd.val[1] = val

!isnothing(Σ) && vnd.bw .= Σ

# updateSolverDataParametric!(vnd, val, Σ)
Expand All @@ -555,6 +576,7 @@ end


##
solveGraphParametric(args...; kwargs...) = solve_RLM(args...; kwargs...)

function DFG.solveGraphParametric!(
fg::AbstractDFG,
Expand All @@ -578,7 +600,7 @@ function DFG.solveGraphParametric!(

updateParametricSolution!(fg, M, v, r, Σ)

return v,r, Σ
return M, v, r, Σ
end


Expand Down
17 changes: 8 additions & 9 deletions src/parametric/services/ParametricUtils.jl
Original file line number Diff line number Diff line change
Expand Up @@ -530,7 +530,7 @@ function _getComponentsCovar(@nospecialize(PM::NPowerManifold), Σ::AbstractMatr
return subsigmas
end

function solveGraphParametric(
function solveGraphParametricOptim(
fg::AbstractDFG;
verbose::Bool = false,
computeCovariance::Bool = true,
Expand Down Expand Up @@ -828,8 +828,7 @@ end
$SIGNATURES
Add parametric solver to fg, batch solve using [`solveGraphParametric`](@ref) and update fg.
"""
function DFG.solveGraphParametric!(
::Val{:Optim},
function solveGraphParametricOptim!(
fg::AbstractDFG;
init::Bool = true,
solveKey::Symbol = :parametric, # FIXME, moot since only :parametric used for parametric solves
Expand All @@ -845,7 +844,7 @@ function DFG.solveGraphParametric!(
initParametricFrom!(fg, initSolveKey; parkey=solveKey)
end

vardict, result, varIds, Σ = solveGraphParametric(fg; verbose, kwargs...)
vardict, result, varIds, Σ = solveGraphParametricOptim(fg; verbose, kwargs...)

updateParametricSolution!(fg, vardict)

Expand Down Expand Up @@ -970,7 +969,7 @@ function getInitOrderParametric(fg; startIdx::Symbol = lsfPriors(fg)[1])
return order
end

function autoinitParametric!(
function autoinitParametricOptim!(
fg,
varorderIds = getInitOrderParametric(fg);
reinit = false,
Expand All @@ -979,16 +978,16 @@ function autoinitParametric!(
kwargs...
)
@showprogress for vIdx in varorderIds
autoinitParametric!(fg, vIdx; reinit, algorithm, algorithmkwargs, kwargs...)
autoinitParametricOptim!(fg, vIdx; reinit, algorithm, algorithmkwargs, kwargs...)
end
return nothing
end

function autoinitParametric!(dfg::AbstractDFG, initme::Symbol; kwargs...)
return autoinitParametric!(dfg, getVariable(dfg, initme); kwargs...)
function autoinitParametricOptim!(dfg::AbstractDFG, initme::Symbol; kwargs...)
return autoinitParametricOptim!(dfg, getVariable(dfg, initme); kwargs...)
end

function autoinitParametric!(
function autoinitParametricOptim!(
dfg::AbstractDFG,
xi::DFGVariable;
solveKey = :parametric,
Expand Down
2 changes: 1 addition & 1 deletion src/services/CalcFactor.jl
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ end

# the same as legacy, getManifold(ccwl.usrfnc!)
getManifold(ccwl::CommonConvWrapper) = ccwl.manifold
getManifold(cf::CalcFactor) = cf.manifold
getManifold(cf::CalcFactor) = getManifold(cf.factor)

function _resizePointsVector!(
vecP::AbstractVector{P},
Expand Down
19 changes: 9 additions & 10 deletions src/services/NumericalCalculations.jl
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,14 @@ function _solveLambdaNumeric_original(
return exp(M, ϵ, hat(M, ϵ, r.minimizer))
end

function cost_optim(M, objResX, Xc)
ϵ = getPointIdentity(M)
X = get_vector(M, ϵ, Xc, DefaultOrthogonalBasis())
p = exp(M, ϵ, X)
residual = objResX(p)
return sum(x->x^2, residual) #TODO maybe move this to CalcFactorNormSq
end

# 1.355700 seconds (11.78 M allocations: 557.677 MiB, 6.96% gc time)
function _solveCCWNumeric_test_SA(
fcttype::Union{F, <:Mixture{N_, F, S, T}},
Expand All @@ -153,18 +161,9 @@ function _solveCCWNumeric_test_SA(
X0c = zero(MVector{getDimension(M),Float64})
X0c .= vee(M, u0, log(M, ϵ, u0))

#TODO check performance
function cost(Xc)
X = hat(M, ϵ, Xc)
p = exp(M, ϵ, X)
residual = objResX(p)
# return sum(residual .^ 2)
return sum(abs2, residual) #TODO maybe move this to CalcFactorNormSq
end

alg = islen1 ? Optim.BFGS() : Optim.NelderMead()

r = Optim.optimize(cost, X0c, alg)
r = Optim.optimize(x->cost_optim(M, objResX, x), X0c, alg)
if !Optim.converged(r)
# TODO find good way for a solve to store diagnostics about number of failed converges etc.
@warn "Optim did not converge (maxlog=10):" r maxlog=10
Expand Down
11 changes: 7 additions & 4 deletions src/services/VariableStatistics.jl
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,15 @@ end

#TODO check performance and FIXME on makemutalbe might not be needed any more
function calcStdBasicSpread(vartype::InferenceVariable, ptsArr::AbstractVector) # {P}) where {P}
_makemutable(s) = s
_makemutable(s::StaticArray{Tuple{S},T,N}) where {S,T,N} = MArray{Tuple{S},T,N,S}(s)
_makemutable(s::SMatrix{N,N,T,D}) where {N,T,D} = MMatrix{N,N,T,D}(s)
# _makemutable(s) = s
# _makemutable(s::StaticArray{Tuple{S},T,N}) where {S,T,N} = MArray{Tuple{S},T,N,S}(s)
# _makemutable(s::SMatrix{N,N,T,D}) where {N,T,D} = MMatrix{N,N,T,D}(s)

# FIXME, silly conversion since Manifolds.std internally replicates eltype ptsArr which doesn't work on StaticArrays
σ = std(vartype, _makemutable.(ptsArr))
# σ = std(vartype, _makemutable.(ptsArr))

μ = mean(vartype, ptsArr, GeodesicInterpolation())
σ = std(vartype, ptsArr, μ)

#if no std yet, set to 1
msst = 1e-10 < σ ? σ : 1.0
Expand Down
Loading

0 comments on commit c49e4b0

Please sign in to comment.