Skip to content
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

Feature/noisemodel rename functions #269

Merged
merged 22 commits into from
Jul 13, 2020

Conversation

yetongumich
Copy link
Contributor

@yetongumich yetongumich commented Apr 3, 2020

  • Add document for the current implementation of robust noise model

  • Add additional test cases to verify the all robust models should behave the same as the quadratic function (except for L2WithDeadZone)

  • Get rid of the distance function in noisemodel, since we already have mahalanobisDistance function. Replace it with error function, which calculates the loss value given the measurement error vector

  • the noisemodel inside robust should be gaussian instead of a general noisemodel.

  • rename several variables so that it agrees with the equations in the document

  • incorporate PR#188 in renaming residual to loss.


This change is Reviewable

@yetongumich yetongumich requested a review from dellaert April 3, 2020 18:09
@yetongumich yetongumich requested a review from ProfFan April 3, 2020 18:25
Copy link
Member

@dellaert dellaert left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Cool. Still unclear why error is needed. When we talked I was suggesting to remove distance, not rename it.

Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements
for (size_t i=0; i<dim_; ++i) // add mu weights on constrained variables
if (constrained(i)) // whiten makes constrained variables zero
w[i] = v[i] * sqrt(mu_[i]); // TODO: may want to store sqrt rather than rebuild
return w.dot(w);
return 0.5 * w.dot(w);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Document change

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Where?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry I forgot to push. It's in the newest commit

@@ -654,6 +654,13 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{
robust_->reweight(A1,A2,A3,b);
}

Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why are we adding this?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Theoretically, the noisemodel inside robust should be Gaussian. However, the old implementation uses a general noisemodel. After changing it to Gaussian, I added this constructor to fit the old API.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't understand, if it is not Gaussian then this conversion will 100% fail.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this complicated matters rather than simplifies them. You can’t change the old API, anyway without a version bump. Please undo the change and throw an exception if not (subclass of) Gaussian - and remove this new function.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It must be Gaussian @ProfFan
I've revised by Frank's suggestion in the new commit.

@@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const {
double JacobianFactor::error(const VectorValues& c) const {
Vector e = unweighted_error(c);
// Use the noise model distance function to get the correct error if available.
if (model_) return 0.5 * model_->distance(e);
if (model_) return model_->error(e);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do we need error? I don’t see it in your document. Also, please rename m to d in your document?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I rethought about it, and I think we still need the error function. Because the way error is calculated varies in different noise models (Gaussian, Robust, Constrained). If we do not have an "error" function inside the noise models, we'll need to implement it in the "error" function of "NoiseModelFactor".

In the document, we already used d to represent the new reweighted Mahalanobis distance

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

2nd

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yetong - we agreed the code would reflect the math. What symbol does “error” correspond to? If there is no corresponding symbol you have two choices: add a symbol in math, or remove this extra function :-)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Got it, will add symbol to document

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, I much prefer if you took a hard look at the document and how the robust (and quadratic) models are used in a factor (which does have an error) and my favorite outcome would be : "wow, we don't need this function at all!"

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure about this. How about discuss about this in our meeting?

ProfFan
ProfFan previously requested changes Apr 5, 2020
@@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const {
double JacobianFactor::error(const VectorValues& c) const {
Vector e = unweighted_error(c);
// Use the noise model distance function to get the correct error if available.
if (model_) return 0.5 * model_->distance(e);
if (model_) return model_->error(e);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

2nd

@@ -654,6 +654,13 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{
robust_->reweight(A1,A2,A3,b);
}

Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust,
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't understand, if it is not Gaussian then this conversion will 100% fail.

gtsam/linear/NoiseModel.cpp Outdated Show resolved Hide resolved
@@ -718,15 +724,18 @@ namespace gtsam {
virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const;

virtual Vector unweightedWhiten(const Vector& v) const {
return noise_->unweightedWhiten(v);
return noise_->whiten(v);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

comments

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So many things going on. Why this change? I think the PR should be more focused on the new math write-up. Is this related?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

After changing the noise_ to gaussian, we can directly use the whiten method.

Here is how things are going on:
In order to agree with the new math, we need to calculate the Mahalanobis distance for the robust noise model. Since mahalanobisDistance is only implmented for Gaussian, I changed the NoiseModel inside robust to Gaussian (previously was general noisemodel), which makes sense since it must be Gaussian.
These changes follow the change of the NoiseModel to Gaussian.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, but unweightedWhiten was not used, right? why is this a thing in this PR? I think we should talk to @mikebosse whether unweightedWhiten is needed at all and have a PR just to remove them, if so?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sounds good, I'll change it back.

Copy link
Member

@dellaert dellaert left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not a satisfactory answer on “error”, see my comment.

@@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const {
double JacobianFactor::error(const VectorValues& c) const {
Vector e = unweighted_error(c);
// Use the noise model distance function to get the correct error if available.
if (model_) return 0.5 * model_->distance(e);
if (model_) return model_->error(e);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yetong - we agreed the code would reflect the math. What symbol does “error” correspond to? If there is no corresponding symbol you have two choices: add a symbol in math, or remove this extra function :-)

Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements
for (size_t i=0; i<dim_; ++i) // add mu weights on constrained variables
if (constrained(i)) // whiten makes constrained variables zero
w[i] = v[i] * sqrt(mu_[i]); // TODO: may want to store sqrt rather than rebuild
return w.dot(w);
return 0.5 * w.dot(w);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Where?

@@ -654,6 +654,13 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{
robust_->reweight(A1,A2,A3,b);
}

Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this complicated matters rather than simplifies them. You can’t change the old API, anyway without a version bump. Please undo the change and throw an exception if not (subclass of) Gaussian - and remove this new function.

@@ -718,15 +724,18 @@ namespace gtsam {
virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const;

virtual Vector unweightedWhiten(const Vector& v) const {
return noise_->unweightedWhiten(v);
return noise_->whiten(v);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So many things going on. Why this change? I think the PR should be more focused on the new math write-up. Is this related?

@dellaert
Copy link
Member

I just checked the updated pdf, and so I still think there is no need for "error" in the noise models, only "loss". Which will take the Mahalanobis distance.

@yetongumich
Copy link
Contributor Author

I just checked the updated pdf, and so I still think there is no need for "error" in the noise models, only "loss". Which will take the Mahalanobis distance.

I see. Currently loss is only defined for robust noise models. Should we make it a general function in noiseModel::Base?

@dellaert
Copy link
Member

That would solve it, right?

@yetongumich
Copy link
Contributor Author

Yes

@dellaert dellaert mentioned this pull request Jul 7, 2020
26 tasks
@ProfFan
Copy link
Collaborator

ProfFan commented Jul 9, 2020

@yetongumich This is blocking 4.0.3 now, could you take a hard look at this PR ASAP?

@yetongumich
Copy link
Contributor Author

@yetongumich This is blocking 4.0.3 now, could you take a hard look at this PR ASAP?

Yes, will take a close look at it this weekend!

@yetongumich
Copy link
Contributor Author

The previous PR was previously blocked by not passing a test in testNonlinearOptimzier.cpp (RobustMeanCalculation).

The modification is reducing the relative error threshold in the Dogleg optimizer parameters. This modification is required because the error of robust noise model increases more slowly as the error becomes larger. Thus, the relative error decrease tend to be small. This issue is not exposed since there was another issue that the error of robust noise model is falsely multiplied by 0.5.

In this PR, since the error of noise model is corrected, the test is also modified to make it pass.

@ProfFan ProfFan requested review from dellaert and ProfFan July 13, 2020 02:57
@ProfFan
Copy link
Collaborator

ProfFan commented Jul 13, 2020

@yetongumich The Cython wrapper is broken:

[ 91%] Building CXX object gtsam_unstable/CMakeFiles/gtsam_unstable.dir/nonlinear/ConcurrentFilteringAndSmoothing.cpp.o
/home/travis/build/borglab/gtsam/build/cython/gtsam/gtsam.cpp: In function ‘int __pyx_pf_5gtsam_5gtsam_17noiseModel_Robust___init__(__pyx_obj_5gtsam_5gtsam_noiseModel_Robust*, PyObject*, PyObject*)’:
/home/travis/build/borglab/gtsam/build/cython/gtsam/gtsam.cpp:148509:130: error: no matching function for call to ‘gtsam::noiseModel::Robust::Robust(boost::shared_ptr<gtsam::noiseModel::mEstimator::Base>&, boost::shared_ptr<gtsam::noiseModel::Base>&)’
         __pyx_t_10 = new gtsam::noiseModel::Robust(__pyx_v_robust->CnoiseModel_mEstimator_Base_, __pyx_v_noise->CnoiseModel_Base_);
                                                                                                                                  ^
In file included from /home/travis/build/borglab/gtsam/build/cython/gtsam/gtsam.cpp:684:0:
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:696:7: note: candidate: gtsam::noiseModel::Robust::Robust(gtsam::noiseModel::mEstimator::Base::shared_ptr, gtsam::noiseModel::Gaussian::shared_ptr)
       Robust(const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise)
       ^
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:696:7: note:   no known conversion for argument 2 from ‘boost::shared_ptr<gtsam::noiseModel::Base>’ to ‘gtsam::noiseModel::Gaussian::shared_ptr {aka boost::shared_ptr<gtsam::noiseModel::Gaussian>}’
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:693:7: note: candidate: gtsam::noiseModel::Robust::Robust()
       Robust() {};
       ^
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:693:7: note:   candidate expects 0 arguments, 2 provided
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:679:11: note: candidate: gtsam::noiseModel::Robust::Robust(const gtsam::noiseModel::Robust&)
     class GTSAM_EXPORT Robust : public Base {
           ^
/home/travis/build/borglab/gtsam/gtsam/linear/NoiseModel.h:679:11: note:   candidate expects 1 argument, 2 provided
cython/CMakeFiles/cythonize_gtsam.dir/build.make:72: recipe for target 'cython/CMakeFiles/cythonize_gtsam.dir/gtsam/gtsam.cpp.o' failed
make[2]: *** [cython/CMakeFiles/cythonize_gtsam.dir/gtsam/gtsam.cpp.o] Error 1
CMakeFiles/Makefile2:7967: recipe for target 'cython/CMakeFiles/cythonize_gtsam.dir/all' failed
make[1]: *** [cython/CMakeFiles/cythonize_gtsam.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 13, 2020

I think this is due to a breaking API change

@yetongumich
Copy link
Contributor Author

Yes. I noticed that, and resolved it in the newest commit. Should be good for the travis check.

Copy link
Member

@dellaert dellaert left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Awesome. Can you also take a look at @mikebosse 's PR after this was merged, and see whether that is completely subsumed in here? Whatever the outcome, please comment in that PR with your take and let @mikebosse close the PR, if needed, or comment on what in that PR still needs to be merged. I'd propose @mikebosse should first merge in develop to see the updated diff.

@dellaert dellaert dismissed ProfFan’s stale review July 13, 2020 17:15

Looked over and seems all comments addressed, don't want to distract you from 4.1

@dellaert dellaert merged commit 73209e6 into develop Jul 13, 2020
@dellaert
Copy link
Member

@yetongumich please delete the branch yourself, I don't have the option it seems. It's weird but there seems to only be a commit.

@yetongumich
Copy link
Contributor Author

@yetongumich please delete the branch yourself, I don't have the option it seems. It's weird but there seems to only be a commit.

I cannot delete the branch. It says can't delete because it has an open PR. Looks like some bug with github.

@varunagrawal varunagrawal deleted the feature/noisemodel_rename_functions branch October 22, 2023 19:54
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants