Skip to content

Commit

Permalink
Merge pull request #302 from JuliaRobotics/maint/mani_v0.10
Browse files Browse the repository at this point in the history
Update to Manifolds v0.10 SE(n, vectors=HybridTangentRepresentation())
  • Loading branch information
Affie authored Oct 3, 2024
2 parents 2ab8e23 + 091425a commit 1899755
Show file tree
Hide file tree
Showing 16 changed files with 47 additions and 47 deletions.
4 changes: 2 additions & 2 deletions Project.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
name = "ApproxManifoldProducts"
uuid = "9bbbb610-88a1-53cd-9763-118ce10c1f89"
keywords = ["MM-iSAMv2", "SLAM", "inference", "sum-product", "belief-propagation", "nonparametric", "manifolds", "functional"]
version = "0.8.5"
version = "0.8.6"

[deps]
Base64 = "2a0f44e3-6c83-55bd-87e4-b1978d98bd5f"
Expand Down Expand Up @@ -42,7 +42,7 @@ CoordinateTransformations = "0.5, 0.6"
Distributions = "0.25"
DocStringExtensions = "0.7, 0.8, 0.9"
KernelDensityEstimate = "0.5.10"
Manifolds = "0.9"
Manifolds = "0.10"
ManifoldsBase = "0.14, 0.15"
NLsolve = "3, 4"
Optim = "1"
Expand Down
2 changes: 1 addition & 1 deletion examples/AMP41_dev.jl
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ end

##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
N = 128


Expand Down
4 changes: 2 additions & 2 deletions examples/dev_BallTreeDensity.jl
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

using StaticArrays, Manifolds, NearestNeighbors, Distances

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
N = 100
# convert point to coordinates
function coords(p)
Expand Down Expand Up @@ -166,7 +166,7 @@ distance(mr.manifold, SVector(1,2),SVector(2,3))
##


M_se2 = SpecialEuclidean(2)
M_se2 = SpecialEuclidean(2; vectors=HybridTangentRepresentation())


sI = SMatrix{3,3,Float64}(diagm(ones(3)))
Expand Down
4 changes: 2 additions & 2 deletions src/entities/ManifoldDefinitions.jl
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ const Euclid3 = TranslationGroup(3)
const Euclid4 = TranslationGroup(4)

# TODO if not easy simplification exists, then just deprecate this
const SE2_Manifold = SpecialEuclidean(2)
const SE3_Manifold = SpecialEuclidean(3)
const SE2_Manifold = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
const SE3_Manifold = SpecialEuclidean(3; vectors=HybridTangentRepresentation())



Expand Down
2 changes: 1 addition & 1 deletion src/services/ManifoldPartials.jl
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ using Manifolds
using ApproxManifoldProducts
# a familiar manifold of translation and rotation in 2D
M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
# make a new partial of only the translation components
Expand Down
22 changes: 11 additions & 11 deletions src/services/ManifoldsOverloads.jl
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ LieGroupManifoldsPirate = Union{
typeof(TranslationGroup(6)),
typeof(SpecialOrthogonal(2)),
typeof(SpecialOrthogonal(3)),
typeof(SpecialEuclidean(2)),
typeof(SpecialEuclidean(3))
typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation())),
typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation()))
}

## ===================================== BASIS PIRATES =====================================
Expand Down Expand Up @@ -46,15 +46,15 @@ get_basis_affine(
)

get_basis_affine(
::typeof(SpecialEuclidean(2))
::typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation()))
) = tuple(
SA[0 -0 1; 0 0 0; 0 0 0.0],
SA[0 -0 0; 0 0 1; 0 0 0.0],
SA[0 -1 0; 1 0 0; 0 0 0.0],
)

get_basis_affine(
::typeof(SpecialEuclidean(3))
::typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation()))
) = tuple(
SA[0 -0 0 1; 0 0 -0 0; -0 0 0 0; 0 0 0 0.0],
SA[0 -0 0 0; 0 0 -0 1; -0 0 0 0; 0 0 0 0.0],
Expand Down Expand Up @@ -141,7 +141,7 @@ parallel_transport_best(


_makeaffine(::AbstractManifold, X) = X
_makeaffine(M::Union{typeof(SpecialEuclidean(2)),typeof(SpecialEuclidean(3))}, X::ArrayPartition) = screw_matrix(M,X)
_makeaffine(M::Union{typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation())),typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation()))}, X::ArrayPartition) = screw_matrix(M,X)

# assumes inputs are Lie algebra tangent vectors represented in matrix form
ad(
Expand Down Expand Up @@ -197,7 +197,7 @@ end


function Ad(
M::Union{typeof(SpecialEuclidean(2)), typeof(SpecialEuclidean(3))},
M::Union{typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation())), typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation()))},
p,
X::ArrayPartition;
use_upstream::Bool = _UPSTREAM_MANIFOLDS_ADJOINT_ACTION # explict to support R&D
Expand Down Expand Up @@ -311,7 +311,7 @@ Ad(
# d is a Lie algebra element (tangent vector) providing the direction of transport
# X is the tangent vector to be transported
function ad(
M::typeof(SpecialEuclidean(3)),
M::typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation())),
d::ArrayPartition,
X::ArrayPartition
)
Expand All @@ -332,7 +332,7 @@ end


function ad(
::typeof(SpecialEuclidean(2)),
::typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation())),
d::ArrayPartition,
)
Vx = SA[d.x[1][2]; -d.x[1][1]]
Expand All @@ -344,7 +344,7 @@ function ad(
end

function ad(
::typeof(SpecialEuclidean(3)),
::typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation())),
d::ArrayPartition,
)
Vx = skew(d.x[1])
Expand All @@ -357,7 +357,7 @@ end


function Ad(
::typeof(SpecialEuclidean(2)),
::typeof(SpecialEuclidean(2; vectors=HybridTangentRepresentation())),
p
)
t = p.x[1]
Expand All @@ -369,7 +369,7 @@ function Ad(
end

function Ad(
::typeof(SpecialEuclidean(3)),
::typeof(SpecialEuclidean(3; vectors=HybridTangentRepresentation())),
p
)
t = p.x[1]
Expand Down
4 changes: 2 additions & 2 deletions test/basic_se3.jl
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ using Test

##

@testset "Test isapprox function on basic SpecialEuclidean(3)" begin
@testset "Test isapprox function on basic SpecialEuclidean(3; vectors=HybridTangentRepresentation())" begin

##

Expand All @@ -17,7 +17,7 @@ using Test
# c_[1,:] .+= 50
# c = kde!(c_)

M = SpecialEuclidean(3)
M = SpecialEuclidean(3; vectors=HybridTangentRepresentation())
u0 = ArrayPartition(zeros(3),[1 0 0; 0 1 0; 0 0 1.0])
ϵ = identity_element(M, u0)
N = 50
Expand Down
20 changes: 10 additions & 10 deletions test/manellic/testManellicTree.jl
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,7 @@ ker = AMP.MvNormalKernel([0], [2.0;;])
)

##
M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
ε = identity_element(M)
Xc = [10, 20, 0.1]
p = exp(M, ε, hat(M, ε, Xc))
Expand Down Expand Up @@ -424,7 +424,7 @@ ys_pdf = pdf(dis, ps)
# lines!(first.(ps), ys_amp)


M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
ε = identity_element(M)
dis = MvNormal([10,20,0.1], diagm([0.5,2.0,0.1].^2))
Cpts = [rand(dis) for _ in 1:128]
Expand All @@ -447,9 +447,9 @@ end


## ========================================================================================
@testset "Test Product the brute force way, SpecialEuclidean(2)" begin
@testset "Test Product the brute force way, SpecialEuclidean(2; vectors=HybridTangentRepresentation())" begin

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
ε = identity_element(M)

Xc_p = [10, 20, 0.1]
Expand Down Expand Up @@ -610,10 +610,10 @@ maj_ang = (angle(Complex(evv.vectors[:,maj_idx]...)) + 2pi) % pi
end


@testset "Rotated covariance product major axis checks, SpecialEuclidean(2)" begin
@testset "Rotated covariance product major axis checks, SpecialEuclidean(2; vectors=HybridTangentRepresentation())" begin
##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
ε = identity_element(M)

Xc_p = [0, 0, 0.0]
Expand Down Expand Up @@ -915,10 +915,10 @@ end



@testset "Multidimensional LOOCV bandwidth optimization, SpecialEuclidean(2)" begin
@testset "Multidimensional LOOCV bandwidth optimization, SpecialEuclidean(2; vectors=HybridTangentRepresentation())" begin
##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
pts = [ArrayPartition(randn(2),Rot_.RotMatrix{2}(0.1*randn()).mat) for _ in 1:64]

bw = [1.0; 1.0; 0.3]
Expand Down Expand Up @@ -954,10 +954,10 @@ end



@testset "Multidimensional LOOCV bandwidth optimization, SpecialEuclidean(3)" begin
@testset "Multidimensional LOOCV bandwidth optimization, SpecialEuclidean(3; vectors=HybridTangentRepresentation())" begin
##

M = SpecialEuclidean(3)
M = SpecialEuclidean(3; vectors=HybridTangentRepresentation())
pts = [ArrayPartition(SA[randn(3)...;],SMatrix{3,3,Float64}(collect(Rot_.RotXYZ(0.1*randn(3)...)))) for _ in 1:64]

bw = SA[1.0; 1.0; 1.0; 0.3; 0.3; 0.3]
Expand Down
2 changes: 1 addition & 1 deletion test/testBasicManiProduct.jl
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ pts = AMP._pointsToMatrixCoords(P12.manifold, pts_)

##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
u0 = ArrayPartition(zeros(2),[1 0; 0 1.0])
ϵ = identity_element(M, u0)

Expand Down
4 changes: 2 additions & 2 deletions test/testLieFundamentals.jl
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ end
@testset "SE(2) Vector transport (w curvature) via Jacobians and Lie adjoints" begin
##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
p = Identity(M)
Xc = 0.5*randn(3)
X = hat(M, p, Xc) # random algebra element
Expand Down Expand Up @@ -208,7 +208,7 @@ end
##


M = SpecialEuclidean(3)
M = SpecialEuclidean(3; vectors=HybridTangentRepresentation())
p = Identity(M)
Xc = 0.5*randn(6)
X = hat(M, p, Xc) # random algebra element
Expand Down
2 changes: 1 addition & 1 deletion test/testMKDStats.jl
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ using Manifolds
@testset "Test basic MKD statistics" begin
##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
u0 = ArrayPartition(zeros(2),[1 0; 0 1.0])
ϵ = identity_element(M, u0)

Expand Down
2 changes: 1 addition & 1 deletion test/testManiProductBigSmall.jl
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ using TensorCast

##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
N = 100
u0 = ArrayPartition([0;0.0],[1 0; 0 1.0])
ϵ = identity_element(M, u0)
Expand Down
2 changes: 1 addition & 1 deletion test/testManifoldConventions.jl
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ import Rotations as _Rot
@testset "test Manifolds.jl conventions" begin
##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
e0 = identity_element(M)

# body to body next
Expand Down
10 changes: 5 additions & 5 deletions test/testManifoldPartial.jl
Original file line number Diff line number Diff line change
Expand Up @@ -57,13 +57,13 @@ M = Manifolds.Rotations(2)
end


@testset "test getManifoldPartial on SpecialEuclidean(2)" begin
@testset "test getManifoldPartial on SpecialEuclidean(2; vectors=HybridTangentRepresentation())" begin

##

M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())

@test getManifoldPartial(M, [1;2;3])[1] == SpecialEuclidean(2)
@test getManifoldPartial(M, [1;2;3])[1] == SpecialEuclidean(2; vectors=HybridTangentRepresentation())

@test getManifoldPartial(M, [1;])[1] == TranslationGroup(1)
@test getManifoldPartial(M, [2;])[1] == TranslationGroup(1)
Expand All @@ -76,7 +76,7 @@ M = SpecialEuclidean(2)

repr = ArrayPartition([0.0; 0], [1 0; 0 1.0])

@test getManifoldPartial(M, [1;2;3], repr)[1] == SpecialEuclidean(2)
@test getManifoldPartial(M, [1;2;3], repr)[1] == SpecialEuclidean(2; vectors=HybridTangentRepresentation())
@test getManifoldPartial(M, [1;2;3], repr)[2] == repr

@test getManifoldPartial(M, [1;], repr)[1] == TranslationGroup(1)
Expand Down Expand Up @@ -117,7 +117,7 @@ end
##

N = 100
M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
u0 = ArrayPartition([0.0; 0], [1 0; 0 1.0])

pts = [exp(M, u0, hat(M, u0, [10 .+ randn(2);randn()])) for i in 1:N]
Expand Down
8 changes: 4 additions & 4 deletions test/testPartialProductSE2.jl
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# test on partial products with SpecialEuclidean(2)
# test on partial products with SpecialEuclidean(2; vectors=HybridTangentRepresentation())

using Manifolds
using ApproxManifoldProducts
Expand All @@ -7,7 +7,7 @@ using BSON

##

@testset "partial product with a SpecialEuclidean(2)" begin
@testset "partial product with a SpecialEuclidean(2; vectors=HybridTangentRepresentation())" begin
##

datafile = joinpath(@__DIR__, "testdata", "partialtest.bson")
Expand All @@ -22,10 +22,10 @@ randN = Float64[]
len = length(pts1)

# define test manifold
M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
e0 = ArrayPartition([0.0;0.0], [1 0; 0 1.0]) # identity_element(M)

# p1 full SpecialEuclidean(2)
# p1 full SpecialEuclidean(2; vectors=HybridTangentRepresentation())
p1 = manikde!(M, pts1)
p1_ = marginal(p1,[1;2])

Expand Down
2 changes: 1 addition & 1 deletion test/testSymmetry.jl
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ a,b = _Rot.RotMatrix(randn()), _Rot.RotMatrix(randn())
@test isapprox( distance(M, a, b), distance(M, b, a), atol = 1e-5)


M = SpecialEuclidean(2)
M = SpecialEuclidean(2; vectors=HybridTangentRepresentation())
a = ArrayPartition(randn(2),_Rot.RotMatrix(randn()))
b = ArrayPartition(randn(2),_Rot.RotMatrix(randn()))
@test isapprox( distance(M, a, b), distance(M, b, a), atol = 1e-5)
Expand Down

0 comments on commit 1899755

Please sign in to comment.