Merge pull request #738 from borglab/feature/update_print_wrap
commit
14314071ff
125
gtsam/gtsam.i
125
gtsam/gtsam.i
|
|
@ -12,6 +12,9 @@ namespace gtsam {
|
||||||
|
|
||||||
// Actually a FastList<Key>
|
// Actually a FastList<Key>
|
||||||
#include <gtsam/inference/Key.h>
|
#include <gtsam/inference/Key.h>
|
||||||
|
|
||||||
|
const KeyFormatter DefaultKeyFormatter;
|
||||||
|
|
||||||
class KeyList {
|
class KeyList {
|
||||||
KeyList();
|
KeyList();
|
||||||
KeyList(const gtsam::KeyList& other);
|
KeyList(const gtsam::KeyList& other);
|
||||||
|
|
@ -379,7 +382,7 @@ class Rot2 {
|
||||||
static gtsam::Rot2 fromCosSin(double c, double s);
|
static gtsam::Rot2 fromCosSin(double c, double s);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "theta") const;
|
||||||
bool equals(const gtsam::Rot2& rot, double tol) const;
|
bool equals(const gtsam::Rot2& rot, double tol) const;
|
||||||
|
|
||||||
// Group
|
// Group
|
||||||
|
|
@ -799,7 +802,7 @@ class Cal3_S2 {
|
||||||
Cal3_S2(double fov, int w, int h);
|
Cal3_S2(double fov, int w, int h);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "Cal3_S2") const;
|
||||||
bool equals(const gtsam::Cal3_S2& rhs, double tol) const;
|
bool equals(const gtsam::Cal3_S2& rhs, double tol) const;
|
||||||
|
|
||||||
// Manifold
|
// Manifold
|
||||||
|
|
@ -1022,7 +1025,7 @@ class PinholeCamera {
|
||||||
const gtsam::Point3& upVector, const CALIBRATION& K);
|
const gtsam::Point3& upVector, const CALIBRATION& K);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "PinholeCamera") const;
|
||||||
bool equals(const This& camera, double tol) const;
|
bool equals(const This& camera, double tol) const;
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
|
|
@ -1160,7 +1163,8 @@ virtual class SymbolicFactor {
|
||||||
|
|
||||||
// From Factor
|
// From Factor
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::SymbolicFactor& other, double tol) const;
|
bool equals(const gtsam::SymbolicFactor& other, double tol) const;
|
||||||
gtsam::KeyVector keys();
|
gtsam::KeyVector keys();
|
||||||
};
|
};
|
||||||
|
|
@ -1173,7 +1177,8 @@ virtual class SymbolicFactorGraph {
|
||||||
|
|
||||||
// From FactorGraph
|
// From FactorGraph
|
||||||
void push_back(gtsam::SymbolicFactor* factor);
|
void push_back(gtsam::SymbolicFactor* factor);
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const;
|
bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool exists(size_t idx) const;
|
bool exists(size_t idx) const;
|
||||||
|
|
@ -1223,7 +1228,8 @@ virtual class SymbolicConditional : gtsam::SymbolicFactor {
|
||||||
static gtsam::SymbolicConditional FromKeys(const gtsam::KeyVector& keys, size_t nrFrontals);
|
static gtsam::SymbolicConditional FromKeys(const gtsam::KeyVector& keys, size_t nrFrontals);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::SymbolicConditional& other, double tol) const;
|
bool equals(const gtsam::SymbolicConditional& other, double tol) const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
|
|
@ -1236,7 +1242,8 @@ class SymbolicBayesNet {
|
||||||
SymbolicBayesNet();
|
SymbolicBayesNet();
|
||||||
SymbolicBayesNet(const gtsam::SymbolicBayesNet& other);
|
SymbolicBayesNet(const gtsam::SymbolicBayesNet& other);
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::SymbolicBayesNet& other, double tol) const;
|
bool equals(const gtsam::SymbolicBayesNet& other, double tol) const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
|
|
@ -1257,7 +1264,8 @@ class SymbolicBayesTree {
|
||||||
SymbolicBayesTree(const gtsam::SymbolicBayesTree& other);
|
SymbolicBayesTree(const gtsam::SymbolicBayesTree& other);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="");
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter);
|
||||||
bool equals(const gtsam::SymbolicBayesTree& other, double tol) const;
|
bool equals(const gtsam::SymbolicBayesTree& other, double tol) const;
|
||||||
|
|
||||||
//Standard Interface
|
//Standard Interface
|
||||||
|
|
@ -1279,7 +1287,8 @@ class SymbolicBayesTree {
|
||||||
// SymbolicBayesTreeClique(const pair<typename ConditionalType::shared_ptr, typename ConditionalType::FactorType::shared_ptr>& result) : Base(result) {}
|
// SymbolicBayesTreeClique(const pair<typename ConditionalType::shared_ptr, typename ConditionalType::FactorType::shared_ptr>& result) : Base(result) {}
|
||||||
//
|
//
|
||||||
// bool equals(const This& other, double tol) const;
|
// bool equals(const This& other, double tol) const;
|
||||||
// void print(string s="") const;
|
// void print(string s = "",
|
||||||
|
// const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const;
|
||||||
// void printTree() const; // Default indent of ""
|
// void printTree() const; // Default indent of ""
|
||||||
// void printTree(string indent) const;
|
// void printTree(string indent) const;
|
||||||
// size_t numCachedSeparatorMarginals() const;
|
// size_t numCachedSeparatorMarginals() const;
|
||||||
|
|
@ -1313,7 +1322,9 @@ class VariableIndex {
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
bool equals(const gtsam::VariableIndex& other, double tol) const;
|
bool equals(const gtsam::VariableIndex& other, double tol) const;
|
||||||
void print(string s="") const;
|
void print(string s = "VariableIndex: ",
|
||||||
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
|
|
@ -1551,7 +1562,9 @@ class VectorValues {
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
size_t dim(size_t j) const;
|
size_t dim(size_t j) const;
|
||||||
bool exists(size_t j) const;
|
bool exists(size_t j) const;
|
||||||
void print(string s="") const;
|
void print(string s = "VectorValues",
|
||||||
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::VectorValues& expected, double tol) const;
|
bool equals(const gtsam::VectorValues& expected, double tol) const;
|
||||||
void insert(size_t j, Vector value);
|
void insert(size_t j, Vector value);
|
||||||
Vector vector() const;
|
Vector vector() const;
|
||||||
|
|
@ -1582,7 +1595,8 @@ class VectorValues {
|
||||||
#include <gtsam/linear/GaussianFactor.h>
|
#include <gtsam/linear/GaussianFactor.h>
|
||||||
virtual class GaussianFactor {
|
virtual class GaussianFactor {
|
||||||
gtsam::KeyVector keys() const;
|
gtsam::KeyVector keys() const;
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
||||||
double error(const gtsam::VectorValues& c) const;
|
double error(const gtsam::VectorValues& c) const;
|
||||||
gtsam::GaussianFactor* clone() const;
|
gtsam::GaussianFactor* clone() const;
|
||||||
|
|
@ -1610,7 +1624,8 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
|
||||||
JacobianFactor(const gtsam::GaussianFactorGraph& graph);
|
JacobianFactor(const gtsam::GaussianFactorGraph& graph);
|
||||||
|
|
||||||
//Testable
|
//Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
void printKeys(string s) const;
|
void printKeys(string s) const;
|
||||||
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
|
|
@ -1659,7 +1674,8 @@ virtual class HessianFactor : gtsam::GaussianFactor {
|
||||||
|
|
||||||
//Testable
|
//Testable
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
void printKeys(string s) const;
|
void printKeys(string s) const;
|
||||||
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
||||||
double error(const gtsam::VectorValues& c) const;
|
double error(const gtsam::VectorValues& c) const;
|
||||||
|
|
@ -1684,7 +1700,8 @@ class GaussianFactorGraph {
|
||||||
GaussianFactorGraph(const gtsam::GaussianBayesTree& bayesTree);
|
GaussianFactorGraph(const gtsam::GaussianBayesTree& bayesTree);
|
||||||
|
|
||||||
// From FactorGraph
|
// From FactorGraph
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const;
|
bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
gtsam::GaussianFactor* at(size_t idx) const;
|
gtsam::GaussianFactor* at(size_t idx) const;
|
||||||
|
|
@ -1775,12 +1792,15 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||||
size_t name2, Matrix T);
|
size_t name2, Matrix T);
|
||||||
|
|
||||||
//Standard Interface
|
//Standard Interface
|
||||||
void print(string s="") const;
|
void print(string s = "GaussianConditional",
|
||||||
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
||||||
|
|
||||||
// Advanced Interface
|
// Advanced Interface
|
||||||
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
gtsam::VectorValues solve(const gtsam::VectorValues& parents) const;
|
||||||
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const;
|
gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents,
|
||||||
|
const gtsam::VectorValues& rhs) const;
|
||||||
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
void solveTransposeInPlace(gtsam::VectorValues& gy) const;
|
||||||
void scaleFrontalsBySigma(gtsam::VectorValues& gy) const;
|
void scaleFrontalsBySigma(gtsam::VectorValues& gy) const;
|
||||||
Matrix R() const;
|
Matrix R() const;
|
||||||
|
|
@ -1797,7 +1817,9 @@ virtual class GaussianDensity : gtsam::GaussianConditional {
|
||||||
GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas);
|
GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas);
|
||||||
|
|
||||||
//Standard Interface
|
//Standard Interface
|
||||||
void print(string s="") const;
|
void print(string s = "GaussianDensity",
|
||||||
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianDensity &cg, double tol) const;
|
bool equals(const gtsam::GaussianDensity &cg, double tol) const;
|
||||||
Vector mean() const;
|
Vector mean() const;
|
||||||
Matrix covariance() const;
|
Matrix covariance() const;
|
||||||
|
|
@ -1810,7 +1832,8 @@ virtual class GaussianBayesNet {
|
||||||
GaussianBayesNet(const gtsam::GaussianConditional* conditional);
|
GaussianBayesNet(const gtsam::GaussianConditional* conditional);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GaussianBayesNet& other, double tol) const;
|
bool equals(const gtsam::GaussianBayesNet& other, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
|
|
||||||
|
|
@ -1845,7 +1868,8 @@ virtual class GaussianBayesTree {
|
||||||
GaussianBayesTree();
|
GaussianBayesTree();
|
||||||
GaussianBayesTree(const gtsam::GaussianBayesTree& other);
|
GaussianBayesTree(const gtsam::GaussianBayesTree& other);
|
||||||
bool equals(const gtsam::GaussianBayesTree& other, double tol) const;
|
bool equals(const gtsam::GaussianBayesTree& other, double tol) const;
|
||||||
void print(string s="");
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter);
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool empty() const;
|
bool empty() const;
|
||||||
size_t numCachedSeparatorMarginals() const;
|
size_t numCachedSeparatorMarginals() const;
|
||||||
|
|
@ -1871,7 +1895,7 @@ class Errors {
|
||||||
Errors(const gtsam::VectorValues& V);
|
Errors(const gtsam::VectorValues& V);
|
||||||
|
|
||||||
//Testable
|
//Testable
|
||||||
void print(string s="");
|
void print(string s = "Errors");
|
||||||
bool equals(const gtsam::Errors& expected, double tol) const;
|
bool equals(const gtsam::Errors& expected, double tol) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
@ -1890,7 +1914,6 @@ class GaussianISAM {
|
||||||
virtual class IterativeOptimizationParameters {
|
virtual class IterativeOptimizationParameters {
|
||||||
string getVerbosity() const;
|
string getVerbosity() const;
|
||||||
void setVerbosity(string s) ;
|
void setVerbosity(string s) ;
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
//virtual class IterativeSolver {
|
//virtual class IterativeSolver {
|
||||||
|
|
@ -1912,7 +1935,6 @@ virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParamete
|
||||||
void setReset(int value);
|
void setReset(int value);
|
||||||
void setEpsilon_rel(double value);
|
void setEpsilon_rel(double value);
|
||||||
void setEpsilon_abs(double value);
|
void setEpsilon_abs(double value);
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/linear/Preconditioner.h>
|
#include <gtsam/linear/Preconditioner.h>
|
||||||
|
|
@ -1934,7 +1956,6 @@ virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters {
|
||||||
#include <gtsam/linear/SubgraphSolver.h>
|
#include <gtsam/linear/SubgraphSolver.h>
|
||||||
virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters {
|
virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters {
|
||||||
SubgraphSolverParameters();
|
SubgraphSolverParameters();
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class SubgraphSolver {
|
virtual class SubgraphSolver {
|
||||||
|
|
@ -1974,7 +1995,7 @@ class Symbol {
|
||||||
Symbol(size_t key);
|
Symbol(size_t key);
|
||||||
|
|
||||||
size_t key() const;
|
size_t key() const;
|
||||||
void print(const string& s) const;
|
void print(const string& s = "") const;
|
||||||
bool equals(const gtsam::Symbol& expected, double tol) const;
|
bool equals(const gtsam::Symbol& expected, double tol) const;
|
||||||
|
|
||||||
char chr() const;
|
char chr() const;
|
||||||
|
|
@ -2054,7 +2075,8 @@ class Ordering {
|
||||||
Ordering(const gtsam::Ordering& other);
|
Ordering(const gtsam::Ordering& other);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::Ordering& ord, double tol) const;
|
bool equals(const gtsam::Ordering& ord, double tol) const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
|
|
@ -2075,7 +2097,8 @@ class NonlinearFactorGraph {
|
||||||
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
|
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);
|
||||||
|
|
||||||
// FactorGraph
|
// FactorGraph
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const;
|
bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool empty() const;
|
bool empty() const;
|
||||||
|
|
@ -2123,7 +2146,8 @@ virtual class NonlinearFactor {
|
||||||
// Factor base class
|
// Factor base class
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
gtsam::KeyVector keys() const;
|
gtsam::KeyVector keys() const;
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
void printKeys(string s) const;
|
void printKeys(string s) const;
|
||||||
// NonlinearFactor
|
// NonlinearFactor
|
||||||
bool equals(const gtsam::NonlinearFactor& other, double tol) const;
|
bool equals(const gtsam::NonlinearFactor& other, double tol) const;
|
||||||
|
|
@ -2153,7 +2177,8 @@ class Values {
|
||||||
void clear();
|
void clear();
|
||||||
size_t dim() const;
|
size_t dim() const;
|
||||||
|
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::Values& other, double tol) const;
|
bool equals(const gtsam::Values& other, double tol) const;
|
||||||
|
|
||||||
void insert(const gtsam::Values& values);
|
void insert(const gtsam::Values& values);
|
||||||
|
|
@ -2242,7 +2267,8 @@ class Marginals {
|
||||||
Marginals(const gtsam::GaussianFactorGraph& gfgraph,
|
Marginals(const gtsam::GaussianFactorGraph& gfgraph,
|
||||||
const gtsam::VectorValues& solutionvec);
|
const gtsam::VectorValues& solutionvec);
|
||||||
|
|
||||||
void print(string s="") const;
|
void print(string s = "Marginals: ", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
Matrix marginalCovariance(size_t variable) const;
|
Matrix marginalCovariance(size_t variable) const;
|
||||||
Matrix marginalInformation(size_t variable) const;
|
Matrix marginalInformation(size_t variable) const;
|
||||||
gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const;
|
gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const;
|
||||||
|
|
@ -2252,8 +2278,7 @@ class Marginals {
|
||||||
class JointMarginal {
|
class JointMarginal {
|
||||||
Matrix at(size_t iVariable, size_t jVariable) const;
|
Matrix at(size_t iVariable, size_t jVariable) const;
|
||||||
Matrix fullMatrix() const;
|
Matrix fullMatrix() const;
|
||||||
void print(string s="") const;
|
void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter) const;
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/nonlinear/LinearContainerFactor.h>
|
#include <gtsam/nonlinear/LinearContainerFactor.h>
|
||||||
|
|
@ -2407,14 +2432,14 @@ virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
|
||||||
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
|
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues);
|
||||||
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params);
|
LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params);
|
||||||
double lambda() const;
|
double lambda() const;
|
||||||
void print(string str) const;
|
void print(string s = "") const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/nonlinear/ISAM2.h>
|
#include <gtsam/nonlinear/ISAM2.h>
|
||||||
class ISAM2GaussNewtonParams {
|
class ISAM2GaussNewtonParams {
|
||||||
ISAM2GaussNewtonParams();
|
ISAM2GaussNewtonParams();
|
||||||
|
|
||||||
void print(string str) const;
|
void print(string s = "") const;
|
||||||
|
|
||||||
/** Getters and Setters for all properties */
|
/** Getters and Setters for all properties */
|
||||||
double getWildfireThreshold() const;
|
double getWildfireThreshold() const;
|
||||||
|
|
@ -2424,7 +2449,7 @@ class ISAM2GaussNewtonParams {
|
||||||
class ISAM2DoglegParams {
|
class ISAM2DoglegParams {
|
||||||
ISAM2DoglegParams();
|
ISAM2DoglegParams();
|
||||||
|
|
||||||
void print(string str) const;
|
void print(string s = "") const;
|
||||||
|
|
||||||
/** Getters and Setters for all properties */
|
/** Getters and Setters for all properties */
|
||||||
double getWildfireThreshold() const;
|
double getWildfireThreshold() const;
|
||||||
|
|
@ -2460,7 +2485,7 @@ class ISAM2ThresholdMap {
|
||||||
class ISAM2Params {
|
class ISAM2Params {
|
||||||
ISAM2Params();
|
ISAM2Params();
|
||||||
|
|
||||||
void print(string str) const;
|
void print(string s = "") const;
|
||||||
|
|
||||||
/** Getters and Setters for all properties */
|
/** Getters and Setters for all properties */
|
||||||
void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& gauss_newton__params);
|
void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& gauss_newton__params);
|
||||||
|
|
@ -2490,13 +2515,13 @@ class ISAM2Clique {
|
||||||
|
|
||||||
//Standard Interface
|
//Standard Interface
|
||||||
Vector gradientContribution() const;
|
Vector gradientContribution() const;
|
||||||
void print(string s="");
|
void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter);
|
||||||
};
|
};
|
||||||
|
|
||||||
class ISAM2Result {
|
class ISAM2Result {
|
||||||
ISAM2Result();
|
ISAM2Result();
|
||||||
|
|
||||||
void print(string str) const;
|
void print(string s = "") const;
|
||||||
|
|
||||||
/** Getters and Setters for all properties */
|
/** Getters and Setters for all properties */
|
||||||
size_t getVariablesRelinearized() const;
|
size_t getVariablesRelinearized() const;
|
||||||
|
|
@ -2512,7 +2537,8 @@ class ISAM2 {
|
||||||
ISAM2(const gtsam::ISAM2& other);
|
ISAM2(const gtsam::ISAM2& other);
|
||||||
|
|
||||||
bool equals(const gtsam::ISAM2& other, double tol) const;
|
bool equals(const gtsam::ISAM2& other, double tol) const;
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
void printStats() const;
|
void printStats() const;
|
||||||
void saveGraph(string s) const;
|
void saveGraph(string s) const;
|
||||||
|
|
||||||
|
|
@ -2544,7 +2570,8 @@ class ISAM2 {
|
||||||
class NonlinearISAM {
|
class NonlinearISAM {
|
||||||
NonlinearISAM();
|
NonlinearISAM();
|
||||||
NonlinearISAM(int reorderInterval);
|
NonlinearISAM(int reorderInterval);
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
void printStats() const;
|
void printStats() const;
|
||||||
void saveGraph(string s) const;
|
void saveGraph(string s) const;
|
||||||
gtsam::Values estimate() const;
|
gtsam::Values estimate() const;
|
||||||
|
|
@ -3016,7 +3043,6 @@ class ShonanAveragingParameters2 {
|
||||||
bool getUseHuber() const;
|
bool getUseHuber() const;
|
||||||
void setCertifyOptimality(bool value);
|
void setCertifyOptimality(bool value);
|
||||||
bool getCertifyOptimality() const;
|
bool getCertifyOptimality() const;
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ShonanAveragingParameters3 {
|
class ShonanAveragingParameters3 {
|
||||||
|
|
@ -3037,7 +3063,6 @@ class ShonanAveragingParameters3 {
|
||||||
bool getUseHuber() const;
|
bool getUseHuber() const;
|
||||||
void setCertifyOptimality(bool value);
|
void setCertifyOptimality(bool value);
|
||||||
bool getCertifyOptimality() const;
|
bool getCertifyOptimality() const;
|
||||||
void print() const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ShonanAveraging2 {
|
class ShonanAveraging2 {
|
||||||
|
|
@ -3330,7 +3355,7 @@ class PreintegratedCombinedMeasurements {
|
||||||
PreintegratedCombinedMeasurements(const gtsam::PreintegrationCombinedParams* params,
|
PreintegratedCombinedMeasurements(const gtsam::PreintegrationCombinedParams* params,
|
||||||
const gtsam::imuBias::ConstantBias& bias);
|
const gtsam::imuBias::ConstantBias& bias);
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "Preintegrated Measurements:") const;
|
||||||
bool equals(const gtsam::PreintegratedCombinedMeasurements& expected,
|
bool equals(const gtsam::PreintegratedCombinedMeasurements& expected,
|
||||||
double tol);
|
double tol);
|
||||||
|
|
||||||
|
|
@ -3371,7 +3396,7 @@ class PreintegratedAhrsMeasurements {
|
||||||
PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs);
|
PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "Preintegrated Measurements: ") const;
|
||||||
bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol);
|
bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol);
|
||||||
|
|
||||||
// get Data
|
// get Data
|
||||||
|
|
@ -3410,7 +3435,8 @@ virtual class Rot3AttitudeFactor : gtsam::NonlinearFactor{
|
||||||
const gtsam::Unit3& bRef);
|
const gtsam::Unit3& bRef);
|
||||||
Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model);
|
Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model);
|
||||||
Rot3AttitudeFactor();
|
Rot3AttitudeFactor();
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
|
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
|
||||||
gtsam::Unit3 nZ() const;
|
gtsam::Unit3 nZ() const;
|
||||||
gtsam::Unit3 bRef() const;
|
gtsam::Unit3 bRef() const;
|
||||||
|
|
@ -3423,7 +3449,8 @@ virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor {
|
||||||
Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ,
|
Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ,
|
||||||
const gtsam::noiseModel::Diagonal* model);
|
const gtsam::noiseModel::Diagonal* model);
|
||||||
Pose3AttitudeFactor();
|
Pose3AttitudeFactor();
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
|
bool equals(const gtsam::NonlinearFactor& expected, double tol) const;
|
||||||
gtsam::Unit3 nZ() const;
|
gtsam::Unit3 nZ() const;
|
||||||
gtsam::Unit3 bRef() const;
|
gtsam::Unit3 bRef() const;
|
||||||
|
|
@ -3435,7 +3462,8 @@ virtual class GPSFactor : gtsam::NonlinearFactor{
|
||||||
const gtsam::noiseModel::Base* model);
|
const gtsam::noiseModel::Base* model);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GPSFactor& expected, double tol);
|
bool equals(const gtsam::GPSFactor& expected, double tol);
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
|
|
@ -3447,7 +3475,8 @@ virtual class GPSFactor2 : gtsam::NonlinearFactor {
|
||||||
const gtsam::noiseModel::Base* model);
|
const gtsam::noiseModel::Base* model);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s="") const;
|
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||||
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::GPSFactor2& expected, double tol);
|
bool equals(const gtsam::GPSFactor2& expected, double tol);
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
|
|
|
||||||
|
|
@ -13,6 +13,7 @@
|
||||||
#include <pybind11/eigen.h>
|
#include <pybind11/eigen.h>
|
||||||
#include <pybind11/stl_bind.h>
|
#include <pybind11/stl_bind.h>
|
||||||
#include <pybind11/pybind11.h>
|
#include <pybind11/pybind11.h>
|
||||||
|
#include <pybind11/functional.h>
|
||||||
#include <pybind11/iostream.h>
|
#include <pybind11/iostream.h>
|
||||||
#include "gtsam/config.h"
|
#include "gtsam/config.h"
|
||||||
#include "gtsam/base/serialization.h"
|
#include "gtsam/base/serialization.h"
|
||||||
|
|
|
||||||
|
|
@ -13,6 +13,7 @@
|
||||||
#include <pybind11/eigen.h>
|
#include <pybind11/eigen.h>
|
||||||
#include <pybind11/stl_bind.h>
|
#include <pybind11/stl_bind.h>
|
||||||
#include <pybind11/pybind11.h>
|
#include <pybind11/pybind11.h>
|
||||||
|
#include <pybind11/functional.h>
|
||||||
#include <pybind11/iostream.h>
|
#include <pybind11/iostream.h>
|
||||||
#include "gtsam/base/serialization.h"
|
#include "gtsam/base/serialization.h"
|
||||||
#include "gtsam/nonlinear/utilities.h" // for RedirectCout.
|
#include "gtsam/nonlinear/utilities.h" // for RedirectCout.
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue