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

Wrap GNC #843

Merged
merged 13 commits into from
Aug 13, 2021
17 changes: 17 additions & 0 deletions gtsam/nonlinear/nonlinear.i
Original file line number Diff line number Diff line change
Expand Up @@ -522,6 +522,14 @@ virtual class DoglegParams : gtsam::NonlinearOptimizerParams {
void setVerbosityDL(string verbosityDL) const;
};

#include <gtsam/nonlinear/GncParams.h>
template<class BaseOptimizerParameters>
Copy link
Collaborator

Choose a reason for hiding this comment

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

You shouldn't be specifying templates as template<class T>, it should be just template<T>.
Same deal for GncOptimizer.

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, thank you Varun

class GncParams {
GncParams(const BaseOptimizerParameters& baseOptimizerParams);
GncParams();
void print(const string& str) const;
};

#include <gtsam/nonlinear/NonlinearOptimizer.h>
virtual class NonlinearOptimizer {
gtsam::Values optimize();
Expand Down Expand Up @@ -551,6 +559,15 @@ virtual class DoglegOptimizer : gtsam::NonlinearOptimizer {
const gtsam::DoglegParams& params);
double getDelta() const;
};

#include <gtsam/nonlinear/GncOptimizer.h>
template<class GncParameters>
class GncOptimizer {
GncOptimizer(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& initialValues,
const gtsam::GncParameters& params);
gtsam::Values optimize();
};

#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
Expand Down