Skip to content

manellic construction uses updateBW instead #291

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
May 13, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/entities/KernelEval.jl
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ abstract type AbstractKernel end
p::MvNormal{T,M}
# TDB might already be covered in p.Σ.chol but having issues with SymPD (not particular to this AMP repo)
""" Manually maintained square root concentration matrix for faster compute, TODO likely duplicate of existing Distrubtions.jl functionality. """
sqrt_iΣ::iM = sqrt(inv(p.Σ))
sqrt_iΣ::iM = sqrt(inv(cov(p)))
""" Nonparametric weight value """
weight::Float64 = 1.0
end
20 changes: 13 additions & 7 deletions src/services/KernelEval.jl
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,22 @@ Statistics.mean(m::MvNormalKernel) = m.μ # mean(m.p) # m.p.μ
Statistics.cov(m::MvNormalKernel) = cov(m.p) # note also about m.sqrt_iΣ
Statistics.std(m::MvNormalKernel) = sqrt(cov(m))

updateKernelBW(k::MvNormalKernel,_bw) = (p=MvNormal(_bw); MvNormalKernel(;μ=k.μ,p,weight=k.weight))
function updateKernelBW(
k::MvNormalKernel,
_bw,
isq_bw = inv(sqrt(_bw))
)
p=MvNormal(_bw)
sqrt_iΣ = typeof(k.sqrt_iΣ)(isq_bw)
return MvNormalKernel(;μ=k.μ,p,sqrt_iΣ,weight=k.weight)
end
updateKernelBW(ekr::MvNormalKernel, ::Nothing) = ekr # avoid ifs for noops


function evaluate(
M::AbstractManifold,
ekr::MvNormalKernel,
p # on manifold point
p, # on manifold point
)
#
dim = manifold_dimension(M)
Expand Down Expand Up @@ -98,10 +108,7 @@ function distanceMalahanobisSq(
basis=DefaultOrthogonalBasis()
)
δc = distanceMalahanobisCoordinates(M,K,q,basis)
# p = mean(K)
# ϵ = identity_element(M, q)
# X = get_vector(M, ϵ, δc, basis)
# return inner(M, p, X, X)
# return inner(M, p, X, X) # did not work as inner gave almost 2x the answer?
return δc'*δc
end

Expand All @@ -114,7 +121,6 @@ function _distance(
p=MvNormal(_p,SVector(ntuple((s)->1,manifold_dimension(M))...))
),
distFnc::Function=distanceMalahanobisSq,
# distFnc::Function=distanceMalahanobisSq,
)
distFnc(M, kernel(p), q)
end
Expand Down
16 changes: 11 additions & 5 deletions src/services/ManellicTree.jl
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ function Base.show(
printstyled(io,"::TK ";color=:magenta)
println(io)
end
printstyled(io, " (depth) : ", floor(Int,log2(length(mt.tree_kernels))),"+1"; color=:light_black)
printstyled(io, " (depth) : 1+", floor(Int,log2(length(mt.tree_kernels))); color=:light_black)
println(io)
printstyled(io, " (blncd) : ", "true : _wip_";color=:light_black)
println(io)
Expand Down Expand Up @@ -600,6 +600,7 @@ function evaluate(
mt::ManellicTree{M,D,N,HL},
pt,
LOO::Bool = false,
force_kbw = nothing
) where {M,D,N,HL}
# # force function barrier, just to be sure dyndispatch is limited
# _F() = getfield(ApproxManifoldProducts,HL.name.name)
Expand All @@ -616,8 +617,10 @@ function evaluate(
# FIXME, is this assuming length(pts) and length(mt.leaf_kernels) are the same?
# FIXME use consolidated getKernelLeaf instead
ekr = mt.leaf_kernels[i]
ekr = updateKernelBW(ekr, force_kbw)
# TODO remember special handling for partials in the future
oneval = mt.weights[i] * evaluate(mt.manifold, ekr, pt)
# leave one out requires kernel weighting to removal of leave out weight
oneval *= !LOO ? 1 : 1/(1-w[i])
sumval += oneval
end
Expand Down Expand Up @@ -645,6 +648,7 @@ function evaluateDensityAtPoints(
)
# evaluate new sampling weights of points in out component

# TODO use agnostic-Dual tree or MonteCarloDualTree evaluation
# vector for storing resulting weights
smw = zeros(length(eval_at_points))
for (i,ev) in enumerate(eval_at_points)
Expand All @@ -666,14 +670,15 @@ end
function expectedLogL(
mt::ManellicTree{M,D,N},
epts::AbstractVector,
LOO::Bool = false
LOO::Bool = false,
force_kbw = nothing
) where {M,D,N}
T = Float64
# TODO really slow brute force evaluation
# TODO really slow brute force evaluation, use agnostic-DualTree or MonteCarloDualTree
eL = MVector{length(epts),T}(undef)
for (i,p) in enumerate(epts)
# LOO skip for leave-one-out
eL[i] = evaluate(mt, p, LOO)
eL[i] = evaluate(mt, p, LOO, force_kbw)
end
# set numerical tolerance floor
zrs = findall(isapprox.(0,eL))
Expand All @@ -693,7 +698,8 @@ end

entropy(
mt::ManellicTree,
) = -expectedLogL(mt, getPoints(mt), true)
force_kbw = nothing
) = -expectedLogL(mt, getPoints(mt), true, force_kbw)


(mt::ManellicTree)(
Expand Down
8 changes: 4 additions & 4 deletions src/services/ManifoldKernelDensity.jl
Original file line number Diff line number Diff line change
Expand Up @@ -120,9 +120,9 @@ function manikde!_manellic(

# Cost function to optimize
_cost(_pts, σ) = begin
# FIXME avoid rebuilding tree at each optim iteration!!!
mtr = buildTree_Manellic!(M, _pts; kernel_bw=reshape(σ,manifold_dimension(M),1), kernel=MvNormalKernel)
entropy(mtr)
# avoid rebuilding tree at each optim iteration!!!
# mtr = buildTree_Manellic!(M, _pts; kernel_bw=reshape(σ,manifold_dimension(M),1), kernel=MvNormalKernel)
entropy(mtree,reshape(σ,manifold_dimension(M),1))
end

# optimize for best LOOCV bandwidth
Expand All @@ -133,7 +133,7 @@ function manikde!_manellic(
(s)->_cost(pts,[s^2;]),
lcov[1], ucov[1], Optim.GoldenSection()
)
best_cov = [Optim.minimizer(res);]
best_cov = [Optim.minimizer(res);;]

# reuse (heavy lift parts of) earlier tree build
# return tree with correct bandwidth
Expand Down
68 changes: 65 additions & 3 deletions test/manellic/testManellicTree.jl
Original file line number Diff line number Diff line change
Expand Up @@ -629,6 +629,22 @@ AMP.expectedLogL(mtree, pts)

@test AMP.expectedLogL(mtree, pts) < Inf

# to enable faster bandwidth selection/optimization
ekr = ApproxManifoldProducts.getKernelLeaf(mtree,1,false)
ekr_ = ApproxManifoldProducts.updateKernelBW(ekr,SA[1.0;;])

@test typeof(ekr) == typeof(ekr_)

# confirm that updating the bandwidths works properly
Σ = [0.1+0.5*rand();;]

mtr = ApproxManifoldProducts.buildTree_Manellic!(M, pts; kernel_bw=Σ,kernel=AMP.MvNormalKernel)
mtr_ = ApproxManifoldProducts.updateBandwidths(mtree, Σ)

#
@test isapprox( mtr([0.0]), mtr_([0.0]); atol=1e-10)
@test isapprox( ApproxManifoldProducts.entropy(mtr), ApproxManifoldProducts.entropy(mtr_); atol=1e-10)


##
end
Expand Down Expand Up @@ -711,15 +727,46 @@ Y = S .|> s->cost(pts,s^2)
# should pass the optimal kbw somewhere in the given range
@test any(0 .< diff(Y))

# and optimize

# and optimize with rebuild tree cost
res = Optim.optimize(
(s)->cost(pts,s^2),
0.05, 3.0, Optim.GoldenSection()
)
best_cov = Optim.minimizer(res)

@test isapprox(0.5, best_cov; atol=0.3)
bcov_ = deepcopy(best_cov)

## Test more efficient updateKernelBW version

cost2(σ) = begin
mtr = ApproxManifoldProducts.updateBandwidths(mtree_0, [σ;;])
AMP.entropy(mtr)
end

# and optimize with "update" kernel bandwith cost
res = Optim.optimize(
(s)->cost2(s^2),
0.05, 3.0, Optim.GoldenSection()
)
@show best_cov = Optim.minimizer(res)

@test isapprox(bcov_, best_cov; atol=1e-3)

# mask bandwith by passing in an alternative

cost3(σ) = begin
AMP.entropy(mtree_0, [σ;;])
end

# and optimize with "update" kernel bandwith cost
res = Optim.optimize(
(s)->cost3(s^2),
0.05, 3.0, Optim.GoldenSection()
)
@show best_cov = Optim.minimizer(res)

@test isapprox(bcov_, best_cov; atol=1e-3)


##
Expand All @@ -734,10 +781,25 @@ end

M = TranslationGroup(1)
# pts = [[0.;],[0.1],[0.2;],[0.3;]]
pts = [1*randn(1) for _ in 1:64]
pts = [1*randn(1) for _ in 1:128]

mkd = ApproxManifoldProducts.manikde!_manellic(M,pts)

best_cov = cov(ApproxManifoldProducts.getKernelLeaf(mkd.belief,1))[1] |> sqrt
@show best_cov

@test isapprox(0.5, best_cov; atol=0.3)

# remember broken code in get w bounds

try
pts = [1*randn(1) for _ in 1:100]
mkd = ApproxManifoldProducts.manikde!_manellic(M,pts)
catch
@test_broken false
end


##
end

Expand Down
Loading