Expose GNC params to python
parent
30412b8110
commit
aee494a24f
|
|
@ -246,7 +246,9 @@ class GTSAM_EXPORT GncOptimizer {
|
||||||
prev_cost = cost;
|
prev_cost = cost;
|
||||||
|
|
||||||
// display info
|
// display info
|
||||||
if (params_.verbosity >= GncParameters::Verbosity::VALUES) {
|
if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) {
|
||||||
|
std::cout << "iter: " << iter << std::endl;
|
||||||
|
std::cout << "mu: " << mu << std::endl;
|
||||||
std::cout << "previous cost: " << prev_cost << std::endl;
|
std::cout << "previous cost: " << prev_cost << std::endl;
|
||||||
std::cout << "current cost: " << cost << std::endl;
|
std::cout << "current cost: " << cost << std::endl;
|
||||||
}
|
}
|
||||||
|
|
@ -255,9 +257,7 @@ class GTSAM_EXPORT GncOptimizer {
|
||||||
if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) {
|
if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) {
|
||||||
std::cout << "final iterations: " << iter << std::endl;
|
std::cout << "final iterations: " << iter << std::endl;
|
||||||
std::cout << "final mu: " << mu << std::endl;
|
std::cout << "final mu: " << mu << std::endl;
|
||||||
std::cout << "final weights: " << weights_ << std::endl;
|
std::cout << "final cost: " << cost << std::endl;
|
||||||
std::cout << "previous cost: " << prev_cost << std::endl;
|
|
||||||
std::cout << "current cost: " << cost << std::endl;
|
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -544,11 +544,23 @@ virtual class DoglegParams : gtsam::NonlinearOptimizerParams {
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/nonlinear/GncParams.h>
|
#include <gtsam/nonlinear/GncParams.h>
|
||||||
|
enum GncLossType {
|
||||||
|
GM /*Geman McClure*/,
|
||||||
|
TLS /*Truncated least squares*/
|
||||||
|
};
|
||||||
|
|
||||||
template<PARAMS>
|
template<PARAMS>
|
||||||
virtual class GncParams {
|
virtual class GncParams {
|
||||||
GncParams(const PARAMS& baseOptimizerParams);
|
GncParams(const PARAMS& baseOptimizerParams);
|
||||||
GncParams();
|
GncParams();
|
||||||
|
void setLossType(const GncLossType type);
|
||||||
|
void setMaxIterations(const size_t maxIter);
|
||||||
|
void setMuStep(const double step);
|
||||||
|
void setRelativeCostTol(double value);
|
||||||
|
void setWeightsTol(double value);
|
||||||
void setVerbosityGNC(const This::Verbosity value);
|
void setVerbosityGNC(const This::Verbosity value);
|
||||||
|
void setKnownInliers(const std::vector<size_t>& knownIn);
|
||||||
|
void setKnownOutliers(const std::vector<size_t>& knownOut);
|
||||||
void print(const string& str) const;
|
void print(const string& str) const;
|
||||||
|
|
||||||
enum Verbosity {
|
enum Verbosity {
|
||||||
|
|
@ -597,6 +609,11 @@ virtual class GncOptimizer {
|
||||||
GncOptimizer(const gtsam::NonlinearFactorGraph& graph,
|
GncOptimizer(const gtsam::NonlinearFactorGraph& graph,
|
||||||
const gtsam::Values& initialValues,
|
const gtsam::Values& initialValues,
|
||||||
const PARAMS& params);
|
const PARAMS& params);
|
||||||
|
void setInlierCostThresholds(const double inth);
|
||||||
|
const Vector& getInlierCostThresholds();
|
||||||
|
void setInlierCostThresholdsAtProbability(const double alpha);
|
||||||
|
void setWeights(const Vector w);
|
||||||
|
const Vector& getWeights();
|
||||||
gtsam::Values optimize();
|
gtsam::Values optimize();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -10,3 +10,4 @@
|
||||||
* Without this they will be automatically converted to a Python object, and all
|
* Without this they will be automatically converted to a Python object, and all
|
||||||
* mutations on Python side will not be reflected on C++.
|
* mutations on Python side will not be reflected on C++.
|
||||||
*/
|
*/
|
||||||
|
#include <pybind11/stl.h>
|
||||||
Loading…
Reference in New Issue