Updated elaboratePoint2KalmanFilter.cpp example and easyPoint2KF bugfix#2031
Updated elaboratePoint2KalmanFilter.cpp example and easyPoint2KF bugfix#2031dellaert merged 4 commits intoborglab:developfrom
Conversation
dellaert
left a comment
There was a problem hiding this comment.
Awesome. I left a bunch of comments with recommendations, and it would be nice to include the output in the Pr comment, but I am approving. I trust you to implement comments where you agree with them.
| // Create new state variable | ||
| Symbol x0('x',0); | ||
| ordering->insert(x0, 0); | ||
| ordering->push_back(x0); |
There was a problem hiding this comment.
Maybe use X(k) everywhere.
using symbol_shorthand::X;
There was a problem hiding this comment.
No, I mean: kill x0, x1, x2 variables. Use X(k) in-place everywhere. Slightly less efficient but good practice for copy/paste in other code.
| Point2 x_initial(0,0); | ||
| SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas((Vec(2) << 0.1, 0.1)); | ||
| PriorFactor<Point2> factor1(x0, x_initial, P_initial); | ||
| SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas((gtsam::Vector2() << 0.1, 0.1).finished()); |
| // Create a JacobianFactor directly - this represents the prior constraint on x0 | ||
| JacobianFactor::shared_ptr factor1( | ||
| new JacobianFactor(x0, P_initial->R(), Vector::Zero(2), | ||
| noiseModel::Unit::Create(2))); |
There was a problem hiding this comment.
Not sure but you might even omit noise model if Unit
| linearizationPoints.insert(x0, x_initial); | ||
| linearFactorGraph->push_back(factor1.linearize(linearizationPoints, *ordering)); | ||
|
|
||
| linearFactorGraph->push_back(factor1); |
There was a problem hiding this comment.
Try to use emplace_shared if you’re creating the shared pointer.
There was a problem hiding this comment.
-> emplace_shared(args)
OR
-> add(args)
so make_shared above is no longer needed.
|
|
||
| Point2 difference(1,0); | ||
| SharedDiagonal Q = noiseModel::Diagonal::Sigmas((Vec(2) << 0.1, 0.1)); | ||
| SharedDiagonal Q = noiseModel::Diagonal::Sigmas((gtsam::Vector2() << 0.1, 0.1).finished()); |
| // = B*u_{t} (for our example) | ||
| Symbol x1('x',1); | ||
| ordering->insert(x1, 1); | ||
| ordering->push_back(x1); |
| SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas((gtsam::Vector2() << 0.1, 0.1).finished()); | ||
|
|
||
| // Create a JacobianFactor directly - this represents the prior constraint on x0 | ||
| JacobianFactor::shared_ptr factor1( |
There was a problem hiding this comment.
auto factor1 = std::make_shared….
| // This can be modeled using the PriorFactor, where the mean is z_{t} and the covariance is R. | ||
| Point2 z1(1.0, 0.0); | ||
| SharedDiagonal R1 = noiseModel::Diagonal::Sigmas((Vec(2) << 0.25, 0.25)); | ||
| SharedDiagonal R1 = noiseModel::Diagonal::Sigmas((gtsam::Vector2() << 0.25, 0.25).finished()); |
| assert(cg1->nrParents() == 0); | ||
| JacobianFactor tmpPrior1 = JacobianFactor(*cg1); | ||
| linearFactorGraph->add(0, tmpPrior1.getA(tmpPrior1.begin()), tmpPrior1.getb() - tmpPrior1.getA(tmpPrior1.begin()) * result[ordering->at(x1)], tmpPrior1.get_model()); | ||
| JacobianFactor::shared_ptr updatedPrior(new JacobianFactor( |
There was a problem hiding this comment.
auto make_shared is the recommended style now
| Point2 x3_update = linearizationPoints.at<Point2>(x3).retract(result[ordering->at(x3)]); | ||
| x3_update.print("X3 Update"); | ||
| VectorValues updatedResult3 = updatedBayesNet3->optimize(); | ||
| Point2 x3_update = linearizationPoints.at<Point2>(x3) + Point2(updatedResult3[x3]); |
There was a problem hiding this comment.
I don’t think you need the Point2()
|
Thanks! I've added your suggestions. Waiting for CI checks to complete. |
|
Adding for reference, expected output is: X1 Predict[ |
|
Two more comments. And, request: update the PR comment with the actual output in a |
|
Added |
|
Very cool, I will merge after CI passes! Next, Python version? We are moving to have Python examples as notebooks, so maybe immediately make a notebook? Will require exposing in wrapper of course. |
|
Great, and yes- working on this! |
|
Congrats on first PR :-) |
Fixed the elaboratePoint2KalmanFilter.cpp with:
Additionally fixed minor bug in easyPoint2KalmanFilter which predicted with wrong factor.