diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index c39cfd22a..9084a50fa 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -63,7 +63,7 @@ class NonlinearFactorGraph { gtsam::KeyVector keyVector() const; template @@ -146,8 +146,8 @@ class Marginals { void print(string s = "Marginals: ", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; - Matrix marginalCovariance(size_t variable) const; - Matrix marginalInformation(size_t variable) const; + gtsam::Matrix marginalCovariance(size_t variable) const; + gtsam::Matrix marginalInformation(size_t variable) const; gtsam::JointMarginal jointMarginalCovariance( const gtsam::KeyVector& variables) const; gtsam::JointMarginal jointMarginalInformation( @@ -155,8 +155,8 @@ class Marginals { }; class JointMarginal { - Matrix at(size_t iVariable, size_t jVariable) const; - Matrix fullMatrix() const; + gtsam::Matrix at(size_t iVariable, size_t jVariable) const; + gtsam::Matrix fullMatrix() const; void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter) const; }; @@ -368,10 +368,10 @@ virtual class GncOptimizer { const gtsam::Values& initialValues, const PARAMS& params); void setInlierCostThresholds(const double inth); - const Vector& getInlierCostThresholds(); + const gtsam::Vector& getInlierCostThresholds(); void setInlierCostThresholdsAtProbability(const double alpha); - void setWeights(const Vector w); - const Vector& getWeights(); + void setWeights(const gtsam::Vector w); + const gtsam::Vector& getWeights(); gtsam::Values optimize(); }; @@ -417,7 +417,7 @@ class ISAM2DoglegParams { }; class ISAM2ThresholdMapValue { - ISAM2ThresholdMapValue(char c, Vector thresholds); + ISAM2ThresholdMapValue(char c, gtsam::Vector thresholds); ISAM2ThresholdMapValue(const gtsam::ISAM2ThresholdMapValue& other); }; @@ -467,7 +467,7 @@ class ISAM2Clique { ISAM2Clique(); // Standard Interface - Vector gradientContribution() const; + gtsam::Vector gradientContribution() const; void print(string s = "", gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter); }; @@ -535,9 +535,9 @@ class ISAM2 { gtsam::PinholeCamera, gtsam::PinholeCamera, gtsam::PinholeCamera, - gtsam::PinholeCamera, Vector, Matrix}> + gtsam::PinholeCamera, gtsam::Vector, gtsam::Matrix}> VALUE calculateEstimate(size_t key) const; - Matrix marginalCovariance(size_t key) const; + gtsam::Matrix marginalCovariance(size_t key) const; gtsam::Values calculateBestEstimate() const; gtsam::VectorValues getDelta() const; double error(const gtsam::VectorValues& x) const; @@ -564,7 +564,7 @@ class NonlinearISAM { void printStats() const; void saveGraph(string s) const; gtsam::Values estimate() const; - Matrix marginalCovariance(size_t key) const; + gtsam::Matrix marginalCovariance(size_t key) const; int reorderInterval() const; int reorderCounter() const; void update(const gtsam::NonlinearFactorGraph& newFactors, @@ -583,7 +583,7 @@ class NonlinearISAM { //************************************************************************* #include template + gtsam::Vector, gtsam::Matrix}> VALUE calculateEstimate(size_t key) const; };