JuliaRobotics / RoME.jl

Robot Motion Estimate: Tools, Variables, and Factors for SLAM in robotics; also see Caesar.jl.
MIT License
64 stars 13 forks source link

Problems using Pose2Point2BearingRange in larger examples #380

Closed lemauee closed 3 years ago

lemauee commented 3 years ago

Hi,

I am experiencing problems when using the Pose2Point2BearingRange Factor on a little larger (150 Pose, 17 Landmarks) example.

The ground truth trajectory looks like this: gt The ground truth for the trajectory and landmarks can be found in these files: gt_traj.txt gt_lm.txt (contains 375 instead of only the 150 robot poses used in the solution below)

The odometry measurements were currupted with the following noise (standard deviation): sigma_x = sigma_y = 0.1; sigma_theta = 5*pi/180;

The bearing range measurements were corrupted with this noise: sigma_bear = 5*pi/180; sigma_range = 0.1;

The solution looks okay until about pose 40: julia_big_uncert_pose40

But after the full round its completely wrong: julia_big_uncert_pose150

Here is the factor graph for this example: fg_big_uncert_150.tar.gz

As a reference of whats possible, using GTSAM yields these results: gtsam_big_uncert

When reducing the measurement noise of odometry and landmarks using factor 0.1 (sigma_new=sigma_old*0.1), the solution looks okay until pose 60: julia_small_uncert_pose60

But at pose 150 it still looks wrong: julia_small_uncert_pose150

Here is the factor graph for this example: fg_small_uncert_150.tar.gz

Solving the same example using Pose2Pose2 measurements to the landmarks works fine for both noise cases: julia_small_uncert_tf_pose150 julia_big_uncert_tf_pose150

The solutions were obtained using the useMsgLikelihoods Parameter set to off, with it on, it takes a lot longer and the results look even worse.

Thanks for having a look at it, maybe a similar example could find its place in the test-folder as it is a pretty common setting close to real data I'd say. Contact me if I forgot anything you need to have a look into It :)

Best, Leo

Affie commented 3 years ago

Hello Leo,

Thanks for opening the issue and for the example graphs, I will be looking into it. There have been a few changes recently and its possible that something broke.

In the mean time you can try repeated solves. A few iterations up and down the tree might be needed. A big part of the drive to close https://github.com/JuliaRobotics/IncrementalInference.jl/issues/1010 will improve this in the future.

lemauee commented 3 years ago

Hi Affie,

what exactly do you mean with repeated solves and how can I trigger them?

Affie commented 3 years ago

You can simply call solveTree!(fg) for a second time.

If you want to compare across solves you can take a look at the 'supersolves' feature (its still experimental but handy https://juliarobotics.org/Caesar.jl/latest/faq/#What-is-supersolve?)

A new value is stored for each solve i.e. :default_1, :default_0 as in:

fg = generateCanonicalFG_lineStep(4)
tree, smt, hists = solveTree!(fg; storeOld=true)
tree, smt, hists = solveTree!(fg; storeOld=true)

julia> listSupersolves(fg)

Set{Symbol} with 4 elements:
  :default
  :graphinit
  :default_1
  :default_0

You can also try clique recycling to speed up the process. Marginalize out variables that are ok or do the solve incrementally. see:

for example:

Affie commented 3 years ago

Just in case you didn't know, you can plot the supersolve with the solveKey kwarg, i.e.

plotSLAM2D(fg; solveKey=:default_1)

It's also handy to compare with what the graph initialized to in :graphinit

Affie commented 3 years ago

I ran a batch parametric solve on your factor graph as a sanity check:

image

The covariances on the landmarks are very large, perhaps check if you made any mistakes on them.

lemauee commented 3 years ago

Hi @Affie ,

thanks for doing the sanity check ;) Did you use the example with big uncertainty or small uncertainty for this? Are you speaking of the covariance of the measurements themselves or the posterior? What tool did you use for the parametric solve?

The measurement variances/standard deviations described in the graph tar file seem okay, 0.01 or 0.1m and 0.009 or 0.09 rad. If you mean the covariance of the posterior, how did you calculate this?

Affie commented 3 years ago

Small uncertainty, the covariance of posterior, and there is a WIP parametric batch solve in IIF. It's not user friendly, yet, and I first had to fix some bugs to get it running again. It's part of an ongoing epic to get it integrated smoothly, the latest work is tracked here: https://github.com/JuliaRobotics/IncrementalInference.jl/issues/467

The covariance is an output of the parametric batch solve, it's calculated using the Hessian matrix from the optimization.

Affie commented 3 years ago

I quickly ran it on you big uncertainty fg: image

BTW, you currenly cannot rename the tar.gz file.

Here are some of the results:

julia> vardict[:l1]
(val = [0.5988914926791957, 0.358331229521665], cov = [16.55541768926432 1.4541500121588415; 1.4541500121481599 18.034438755679528])

julia> vardict[:x100]
(val = [2.9097055821088134, 0.8530596188376324, 0.9319651360539617], cov = [2.2223584644569336 -0.6885930120588244 0.5184280256182754; -0.6885930120678446 3.0179889660024277 -0.48413906103614074; 0.5184280256221653 -0.4841390610376167 0.40957624454493247])

Edit: I didn't initialize it, you should get closer with initialization.

lemauee commented 3 years ago

I just calculated the variances of the bearing and range measurements from the "ground truth measurements" and my noisy measurements and they were what I input to my dataset-generation-tool. But this still does not confirm that my "ground truth measurements" must be correct (although the first 60 poses work fine). Do you have a tool lying around that could also generate noisy measurements from my GT? Then we could completely eliminate this source of error.

What still makes me wonder, is that GTSAM solves both these examples correctly as shown in the first comment, but i had a robust cost function on when doing this, so maybe errors in the measurements were handled by this. I could do a solve there with only the gaussian cost function.

Affie commented 3 years ago

Perhaps share your script for generating the fg from the ground truth and I'll have a look when I get a chance again. I'm working on updates to IIF and RoME and I used your data to test with, a two birds with one stone kind of thing.

lemauee commented 3 years ago

The tool for generating the measurements the is written in matlab because i also run gtsam from there, i actually read a matfile in julia. Its pretty bulky and might be more confusing than helping ;) But generating bearing range measurements from gt should be a quick thing in Julia, I think that is the option to go. I will report back when i have a function that takes the gt text files, noise information and association information as input and builds a fg from this.

lemauee commented 3 years ago

Here it goes:

## Read Gt Input from files

using CSV

associationLm = CSV.File("association_lm.txt", header=["iPose", "jLm"])
gtLm = CSV.File("gt_lm.txt", header=["x", "y", "θ"])
gtTraj = CSV.File("gt_traj.txt", header=["x", "y", "θ"])

## Generate bearing range measurements from groundtruth

using CoordinateTransformations, TransformUtils, LinearAlgebra

Tinv(x,y,θ) = inv(Translation(x,y) ∘ LinearMap(R(θ)))

mTrajGt = [Vector{Float64}(undef,3) for _ = 1:length(gtTraj)]
mLmGt = [Dict{Int,Vector{Float64}}() for _ = 1:length(gtTraj)]

for kPose = 1:length(gtTraj)

    # odometry
    if kPose > 1 # no odemetry for first pose, prior instead
        trans = Tinv(gtTraj[kPose-1].x,gtTraj[kPose-1].y,gtTraj[kPose-1].θ)([gtTraj[kPose].x, gtTraj[kPose].y])
        rot = wrapRad(gtTraj[kPose].θ - gtTraj[kPose-1].θ)
        mTrajGt[kPose] = vcat(trans,rot)
    end

    # landmark measurements
    lmIdx = associationLm.jLm[findall(associationLm.iPose .== kPose)]
    for kLm = lmIdx
        trans = Tinv(gtTraj[kPose].x,gtTraj[kPose].y,gtTraj[kPose].θ)([gtLm[kLm].x, gtLm[kLm].y])
        bearing = atan(trans[2],trans[1])
        range = norm(trans)
        mLmGt[kPose][kLm] = [bearing, range]
    end
end

## Add noise to ground truth measurements

using Distributions, Random

Random.seed!(42); # reproducibility

ΣOdo = Diagonal([0.01,0.01,0.5*pi/180].^2)
σBearing = 0.5*pi/180
σRanging = 0.01

noiseOdo = MvNormal([0,0,0],ΣOdo)
noiseBearing = Normal(0,σBearing)
noiseRanging = Normal(0,σRanging)

mTrajNoisy = [Vector{Float64}(undef,3) for _ = 1:length(gtTraj)]
mLmNoisy = [Dict{Int,Vector{Float64}}() for _ = 1:length(gtTraj)]

for kPose = 1:length(gtTraj)

    # odometry
    if kPose > 1 # no odemetry for first pose, prior instead
        mTrajNoisy[kPose] = mTrajGt[kPose] + vec(rand(noiseOdo,1))
    end

    # landmark measurements
    for kLm = keys(mLmGt[kPose])
        mLmNoisy[kPose][kLm] = mLmGt[kPose][kLm] + vcat(rand(noiseBearing,1), rand(noiseRanging,1))
    end
end

## Build fg from measurements and solve incrementally

using RoME, RoMEPlotting

endPose = 150;
fg = LightDFG{SolverParams}(solverParams=SolverParams(logpath="br_issue"))
getSolverParams(fg).useMsgLikelihoods = false

function addVarIfMissing!(fg,symbol,type,tags)
    if (symbol in ls(fg)) == false
        @info "adding missing variable $(symbol)"
        addVariable!(fg, symbol, type, tags = tags)
    end
end

for kPose = 1:endPose

    global fg,tree,smt,hist

    # odometry
    if kPose > 1 # no odometry for first pose
        fromPose = Symbol("x", kPose-1)
        toPose = Symbol("x", kPose)
        addVarIfMissing!(fg, fromPose, Pose2, [:POSE])
        addVarIfMissing!(fg, toPose, Pose2, [:POSE])   
        addFactor!(fg, [fromPose, toPose], Pose2Pose2(MvNormal(mTrajNoisy[kPose], ΣOdo)), graphinit = false)
        initManual!(fg, toPose, [Symbol("x",kPose-1,"x",kPose,"f",1)]) # doing this because I initlialize the same way in GTSAM
    else # prior instead
        addVariable!(fg, :x1, Pose2)
        addFactor!(fg, [:x1], PriorPose2(MvNormal([gtTraj[1].x, gtTraj[1].y, gtTraj[1].θ], Diagonal([0.01,0.01,0.5*pi/180].^2))))
    end

    # landmark measurements
    fromPose = Symbol("x", kPose)
    for kLm = collect(keys(mLmGt[kPose]))
        toLm = Symbol("l", kLm)
        addVarIfMissing!(fg, fromPose, Pose2, [:POSE])
        addVarIfMissing!(fg, toLm, Point2, [:LANDMARK])  
        distBearing = Normal(mLmNoisy[kPose][kLm][1],σBearing)
        distRange = Normal(mLmNoisy[kPose][kLm][2],σRanging)
        addFactor!(fg, [fromPose, toLm], Pose2Point2BearingRange(distBearing,distRange))
    end

    # solve
    if kPose > 1 # not on first solve
        tree, smt, hist = solveTree!(fg, tree)
    else # first solve
        tree, smt, hist = solveTree!(fg)
    end

    # save
    prefix = lpad(kPose,5,'0')
    saveDFG(fg, "$(getLogPath(fg))/$(prefix)_fg")

    # plot
    pl = plotSLAM2D(fg;contour=false)
    push!(pl, Coord.cartesian(fixed=true),style(background_color=RGB(1,1,1)))
    @async draw(PNG("$(getLogPath(fg))/$(prefix)_poses_landms.png", 20cm, 20cm), pl)

end

The three data files needed are: gt_traj.txt gt_lm.txt association_lm.txt

This time, the inference for the small odometry and landmark measurement noise goes well until pose 140 00140_poses_landms 00140_fg.tar.gz

Unfortunately, at pose 150 it starts to deviate from the gt as previously on pose 60. 00150_poses_landms 00150_fg.tar.gz

I blame the later deviation on the randomness of data generation and the sampling-based nature of mmiSAM itself. I will run the example with the larger noises now and see how that goes. Suggestions on the improvement of the example code are always welcome :)

Best, Leo

Affie commented 3 years ago

Hi Leo, I quickly ran 00150_fg with the parametric batch solve and it looks fine now, here is the result:

image

julia> vardict[:x150]
(val = [4.262354125628386, 0.14021709193974205, -3.1276065053502657], cov = [0.005694615341690437 -0.004918898079872337 0.00189115140358998; -0.0049188980798741235 0.005320366826828777 -0.0017820498010356156; 0.0018911514035903259 -0.0017820498010353246 0.0008248574220506626])

julia> vardict[:x1]
(val = [7.158420610276514, 3.387868629288589, -1.366707199620146], cov = [9.990368460464983e-5 2.585305984293597e-8 -3.832437599377215e-7; 2.585305984119516e-8 0.00010006370609428759 -2.435159610124383e-7; -3.832437599317601e-7 -2.435159610014308e-7 7.649298333790687e-5])

julia> vardict[:l1]
(val = [0.6669839865930746, 0.4453027518205175], cov = [0.0045973221891050685 -0.010292723535269771; -0.010292723535272358 0.027494856329173038])

julia> vardict[:l10]
(val = [4.413175285434976, 3.3379461401884556], cov = [0.0008762888142592431 0.0007804164890493029; 0.0007804164890486069 0.004742525658324642])

I'll look into more detail at a later stage.

lemauee commented 3 years ago

Hi,

Thanks for doing the parametric solve. The 00150_fg already was pretty close to the solution and served as a pretty good initialization for the parametric solve, I'd say.

The example with more noise

ΣOdo = Diagonal([0.1,0.1,5*pi/180].^2)
σBearing = 5*pi/180
σRanging = 0.1

starts to look really ugly after pose 30 again: 00030_poses_landms 00030_fg.tar.gz

It ran all day (but just on one core because I needed my machine for other things too and didn't bother to run it somewhere else ;), I'm currently at pose 136/150 and it looks pretty similar to the one in my first post: 00136_poses_landms 00136_fg.tar.gz

An incremental (pose by pose, for initialization) parametric solve of this would be quite interesting. I will upload the 00150_fg before I go to sleep ;)

Affie commented 3 years ago

I quickly ran 00136_fg for you with the parametric solve. The data looks ok to me. It does look like there was something wrong with the previous datasets. I still have to look in more detail, I will as soon as I get a chance and give you an update.

image

lemauee commented 3 years ago

Thanks for doing the parametric solve again, it looks as i would expect (close to the GTSAM solution from the first post). Thanks for continuing to look into this, let me know if there is anything I can contribute.

Here's the nonparametric solution for pose 150: 00150_poses_landms 00150_fg.tar.gz

lemauee commented 3 years ago

Hi @Affie ,

I just ran 10 repeated solves on the small uncertainty 00150_fg as you suggested in a previous post: poses_landms_resolve_10

Unfortunately, this did not result in a better solution. Maybe marginalizing out old robot poses is the way to go as you also suggested, although revisiting the same landmark later on also should improve their accuracy.

Best, Leo

Affie commented 3 years ago

Hi Leo, I modified your example a bit and set it up to run repeated solves. I had to initialise using only the Poses first and then the Landmarks:

fg.solverParams.graphinit = false
...
# fil in fg but don't solve or init
...
vars = sortDFG(ls(fg, tags=[:POSE]))
doautoinit!(fg, vars)
ensureAllInitialized!(fg)

We will have to look into why it's not initialising well with graphinit.

On repeated solving: at some point it may get worse caused by parasitics.

Init: init

Solve 1: solve1

Solve 3: solve3

lemauee commented 3 years ago

Thanks for this, at least we know now nothings wrong with the example anymore ;)

Unfortunately the setting I'm after in the end is not the batch problem but the fully incremental solution ("online SLAM"), and initializing only using the robot poses/odometry will not work for a larger odometry noise. Some sort of parasitics in this incremental setting (my example code did this in the first place, I suppose you took the 00150_fg, initialized and solved it again) seem to be breaking the solution I'd say. I guess what I still could try is performing repeated solves in every iteration (this would take a lot of time though) and/or marginalizing out old poses to maybe get rid of some parasitic effects (just a guess, maybe you have an idea towards this)

What bothered me from the beginning is that mmiSAM is always pretty sure about its sometimes not so accurate solution ;) The kernels of a particular pose or landmark always have very little spread, if I estimate the covariance of the kernels its always way smaller than what a parametric solution (GTSAM) yields. If there are no particles supporting the right mode in this and the adjacent variables, its bound to break at some point.

Affie commented 3 years ago

I believe JuliaRobotics/IncrementalInference.jl#1010 together with tree initialization will help solve this. Changes in either the factor (not recommended: to keep it compatible with parametric) or solver might be needed for graph initialization and solving without #1010.

Here is a MWE:

fg = initfg()
addVariable!(fg, :x1, Pose2)
addVariable!(fg, :l1, Point2)
addFactor!(fg, [:l1], PriorPoint2(MvNormal([0.,0], [0.01, 0.01])))
addFactor!(fg, [:x1; :l1], Pose2Point2BearingRange(Normal(-pi, 0.01), Normal(1.0, 0.1)))
ensureAllInitialized!(fg)
pl = plotSLAM2D(fg)

In this case, there is not enough information and the pose x1 is initialized wrong as: image

It should be closer to: image

Edit: updates to the solver that can improve this is tracked in this issue: https://github.com/JuliaRobotics/IncrementalInference.jl/issues/1051

So work is in progress in IIF to improve cases like this in:

Affie commented 3 years ago

@lemauee, Thanks for the example, we will revisit this after the above issues are resolved. The basic case can also be implemented in the CI tests.

Affie commented 3 years ago

@dehann, perhaps the MWE above and this one can be helpful in testing work in JuliaRobotics/IncrementalInference.jl#1010, we can also implement it in the tests:

fg = initfg()
pr_noise = [0.01, 0.01, 0.001]
od_noise = [0.2;0.2;0.2]
σ_bearing = 0.008
σ_range = 0.01

addVariable!(fg, :x0, Pose2)
prpo = MvNormal([0,0,-pi], pr_noise)
addFactor!(fg, [:x0], PriorPose2(MvNormal(rand(prpo), pr_noise)))

addVariable!(fg, :l1, Point2, tags=[:LANDMARK])
addVariable!(fg, :l2, Point2, tags=[:LANDMARK])
p2br = Pose2Point2BearingRange(Normal(pi/4 + rand(Normal(0,σ_bearing)), σ_bearing),
                               Normal(sqrt(2) + rand(Normal(0,σ_range)), σ_range))
addFactor!(fg, [:x0; :l1], p2br)

addVariable!(fg, :x1, Pose2)
pp = MvNormal([1.0,0,0], od_noise)
addFactor!(fg, [:x0,:x1], Pose2Pose2(MvNormal(rand(pp), od_noise)))

p2br = Pose2Point2BearingRange(Normal(pi/2 + rand(Normal(0,σ_bearing)), σ_bearing),
                               Normal(1 + rand(Normal(0,σ_range)), σ_range))
addFactor!(fg, [:x1; :l1], p2br)

p2br = Pose2Point2BearingRange(Normal(-pi/2 + rand(Normal(0,σ_bearing)), σ_bearing),
                               Normal(1 + rand(Normal(0,σ_range)), σ_range))
addFactor!(fg, [:x1; :l2], p2br)

addVariable!(fg, :x2, Pose2)
pp = MvNormal([1.0,0,0], od_noise)
addFactor!(fg, [:x1,:x2], Pose2Pose2(MvNormal(rand(pp), od_noise)))

p2br = Pose2Point2BearingRange(Normal(3pi/4 + rand(Normal(0,σ_bearing)), σ_bearing),
                               Normal(sqrt(2) + rand(Normal(0,σ_range)), σ_range))
addFactor!(fg, [:x2; :l1], p2br)

p2br = Pose2Point2BearingRange(Normal(-3pi/4 + rand(Normal(0,σ_bearing)), σ_bearing),
                               Normal(sqrt(2) + rand(Normal(0,σ_range)), σ_range))
addFactor!(fg, [:x2; :l2], p2br)
dehann commented 3 years ago

Hi, thanks for listing and MWEs -- that is very helpful. We can try get IIF 1051 in before to help here. In general, I'm making progress on IIF 1010, and we recently cleared one of the main blockers for combined AMP 41, RoME 244, and IIF 467. We did recently make improvements to BearingRange as part of consolidation on IIF 467. Will try close that out and tag IIF v0.21 as soon as possible. Johan is working on closing out 467 where he found and think mostly resolved a dispatch issue (but note it will be a breaking change for user factor API in IIF v0.21).

lemauee commented 3 years ago

Thanks for the update, a breaking change in the user factor API should not be a big problem as I'm reading most of my examples from file, so only that parser should need to change. Changing it for the examples in this issue also should not be a problem.

dehann commented 3 years ago

Darn, wow -- I did break something, but have a promising solution. I think the regression stems from one of the preparation steps required for JuliaRobotics/IncrementalInference.jl#1010, however, the fix for JuliaRobotics/IncrementalInference.jl#1051 gets around that problem. Will explain more technical details once IIF 1010 is done (will be easier/quick to do then), but a short write-up is given at the end of this comment.

Comparative Results

So from the MWE above, here are the new results (3 good example cases, 2 control bad cases). Solving and drawing MWE with:

fg = initfg()
# FIX, NEW PARAMETER COMING IN IIF v0.21.1 and RoME v0.13.0
getSolverParams(fg).inflation = 3.0 # default=3.0 as new parameter, only effects nonparametric 

# build the graph

# solve the graph with two techniques (nonparametric and parametric)
solveGraph!(fg) # alias for solveTree!
IIF.solveFactorGraphParametric!(fg)

# draw both results and stack
pl1 = plotSLAM2D(fg, solveKey=:default, drawPoints=true, drawEllipse=true, drawContour=false, xmin=-2.5,xmax=0,ymin=-1.5,ymax=1.5)
pl2 = plotSLAM2D(fg, solveKey=:parametric, drawPoints=false, drawContour=false, xmin=-2.5,xmax=0,ymin=-1.5,ymax=1.5)

# nonparametric above, parametric below
vstack(pl1, pl2)

New Working Cases

Screenshot from 2021-02-13 21-14-57


Screenshot from 2021-02-13 21-09-13


Screenshot from 2021-02-13 21-11-30

Old Broken Cases

This is with, and clearly the results are broken:


getSolverParams(fg).inflation = 0.0 # equivalent to when this issue was opened

Screenshot from 2021-02-13 21-12-55


Screenshot from 2021-02-13 21-13-59

New tests

I will add the new test to RoME v0.13.0 (thanks to the examples, input, and patience from both @lemauee and @Affie, thanks!)

Next Steps

@lemauee ,

Once we have IIF v0.21.1, and RoME v0.13.0 tagged. Would you mind trying this out again please and let us know if it helps / fixes at least some of your struggles on this issue?

I must apologize for this issue found by Leo. I think we were pushing bit too fast for #1010 and a silly regression slipped through testing which had an outsized negative impact on solve quality. Regardless, the good news is this MWE example will now be permanently included in the tests to prevent future occurrences. Will link that PR below.

For transparency, I think, but not yet confirmed, the issue might have been caused by this prep work for what is now recorded as IIF 1010: https://github.com/JuliaRobotics/IncrementalInference.jl/commit/99246d701c5da8bef4cbc4ac03ac7adc8f796913

Short version is, to do 1010 the the naive Gibbs method for injecting entropy is too simplistic. 1010 requires more advanced tracking of the correlations within the joint over upward tree clique separators. Turns out, what I believe the problem was here, is that preparation step removed too much entropy and the stochastic assumptions for Gibbs sampling broke down. The fix for IIF 1051 is a different point in inference process whereby entropy can be injected in the overall process. It clearly has a direct remarkable affect and restores the behavior in BearingRange cases as they were in the past and should be.

We were a little in no-mans-land as we transit from naive Gibbs sampling to joint message propagation.

Best, Dehann

dehann commented 3 years ago

One more heads up, I need to do a little more with Pose3D to make sure that still works right. Should be able to tag in a day or two.

dehann commented 3 years ago

Another update, it's possible that there is a second hidden bug that is showing up following the new inflation approach. I already added more tests to RoME (will link the commit below), and working to get that resolved today. This second issue relates to convolution numerical calculations on Sphere1 recovering a trivial (but incorrect) result on a small percentage of the kernels. If .inflation is made large on Euler representation, the likelihood of samples ending in the trivial case increases. If .inflation is small on Euler representation dimensions, then trivial cases is avoided 99.999% of the time. A few kernels caught in trivial case will not disrupt the solution. The issue occurs when a large fraction of the samples get "caught" in the trivial case. Will annotate separately when a clear issue/fix can be highlighted.

BTW, fixing #244 should completely avoid this issue (i.e. completely remove Euler angles during all stages of inference), but until then I will resolve via fix or workaround so regular use can continue. For those following, we are at the end of an old generation in IIF and RoME, and busy transitioning to a whole new generation of internal code. I'd like to leave the old code working well enough, but then focus energy on quality with the "new internals".

lemauee commented 3 years ago

Thanks for the insight on this! Too little entropy in the Gibbs sampling process seems like a good explanation. So JuliaRobotics/IncrementalInference.jl#1051 can be used as a "short term fix", but in the long run JuliaRobotics/IncrementalInference.jl#1010 should be able to work without this trick?

@Affie already mentioned the transition from naive Gibbs sampling to joint message propagation in our videocall 2 weeks ago. This is what I turn on and off using the useMsgLikelihood parameter, am I right? His suggestion was that I should only try it when using just Pose2Pose2 factors (or something else connecting variables of similar dimension)

I will wait for RoME.jl v0.13.0 to be tagged and then get right to running the examples again. Is there a good way to get a notification on new releases automatically?

Best, Leo

Affie commented 3 years ago

Hi Leo, Gibbs sampling is still used in the cliques even with useMsgLikelihood on. I suspect some sort of inflation will always be required. Especially with the consolidation that is happening in cases like this (the 2pi*rand(n) part): https://github.com/JuliaRobotics/RoME.jl/blob/9a25267a2e0fc6ab12c48c8a09510ed595ca2063/src/factors/Range2D.jl#L13-L15

I will wait for RoME.jl v0.13.0 to be tagged and then get right to running the examples again. Is there a good way to get a notification on new releases automatically?

You can watch a specific git repository and turn on notices on releases, or the announcements channel in Slack is also up to date.

lemauee commented 3 years ago

Thanks for the hint, I'll get notified now on slack and github so i shouldnt miss out :)

dehann commented 3 years ago

Oops, think automation closed this -- Leo, please close this if results are coming back fine.

lemauee commented 3 years ago

The 150-pose example posted in this issue now solves like expected: 00150_poses_landms

Even the one with more noise

ΣOdo = Diagonal([0.1,0.1,5*pi/180].^2)
σBearing = 5*pi/180
σRanging = 0.1

looks good: 00150_poses_landms

I'll test the multimodal stuff I originally wanted to do with this factor tomorrow and report on this, but for the unimodal case this works good now. Thanks for fixing again! :)

lemauee commented 3 years ago

Using treeinit did not work for me on this example: 00150_poses_landms But as the standard graphinit does fine, this should be no issue for me.