Fixed gtsam_unstable matlab wrapper

release/4.3a0
Richard Roberts 2013-08-12 22:26:37 +00:00
parent 175965a6bf
commit 5d0f8399ed
1 changed files with 125 additions and 125 deletions

View File

@ -466,132 +466,132 @@ virtual class DiscreteEulerPoincareHelicopter : gtsam::NonlinearFactor {
//************************************************************************* //*************************************************************************
// nonlinear // nonlinear
//************************************************************************* //*************************************************************************
#include <gtsam_unstable/nonlinear/sequentialSummarization.h> // #include <gtsam_unstable/nonlinear/sequentialSummarization.h>
gtsam::GaussianFactorGraph* summarizeGraphSequential( // gtsam::GaussianFactorGraph* summarizeGraphSequential(
const gtsam::GaussianFactorGraph& full_graph, const gtsam::KeyVector& indices); // const gtsam::GaussianFactorGraph& full_graph, const gtsam::KeyVector& indices);
gtsam::GaussianFactorGraph* summarizeGraphSequential( // gtsam::GaussianFactorGraph* summarizeGraphSequential(
const gtsam::GaussianFactorGraph& full_graph, const gtsam::Ordering& ordering, const gtsam::KeySet& saved_keys); // const gtsam::GaussianFactorGraph& full_graph, const gtsam::Ordering& ordering, const gtsam::KeySet& saved_keys);
#include <gtsam_unstable/nonlinear/FixedLagSmoother.h> // #include <gtsam_unstable/nonlinear/FixedLagSmoother.h>
class FixedLagSmootherKeyTimestampMapValue { // class FixedLagSmootherKeyTimestampMapValue {
FixedLagSmootherKeyTimestampMapValue(const gtsam::Key& key, double timestamp); // FixedLagSmootherKeyTimestampMapValue(const gtsam::Key& key, double timestamp);
FixedLagSmootherKeyTimestampMapValue(const gtsam::FixedLagSmootherKeyTimestampMapValue& other); // FixedLagSmootherKeyTimestampMapValue(const gtsam::FixedLagSmootherKeyTimestampMapValue& other);
}; // };
//
class FixedLagSmootherKeyTimestampMap { // class FixedLagSmootherKeyTimestampMap {
FixedLagSmootherKeyTimestampMap(); // FixedLagSmootherKeyTimestampMap();
FixedLagSmootherKeyTimestampMap(const gtsam::FixedLagSmootherKeyTimestampMap& other); // FixedLagSmootherKeyTimestampMap(const gtsam::FixedLagSmootherKeyTimestampMap& other);
//
// Note: no print function // // Note: no print function
//
// common STL methods // // common STL methods
size_t size() const; // size_t size() const;
bool empty() const; // bool empty() const;
void clear(); // void clear();
//
double at(const gtsam::Key& key) const; // double at(const gtsam::Key& key) const;
void insert(const gtsam::FixedLagSmootherKeyTimestampMapValue& value); // void insert(const gtsam::FixedLagSmootherKeyTimestampMapValue& value);
}; // };
//
class FixedLagSmootherResult { // class FixedLagSmootherResult {
size_t getIterations() const; // size_t getIterations() const;
size_t getNonlinearVariables() const; // size_t getNonlinearVariables() const;
size_t getLinearVariables() const; // size_t getLinearVariables() const;
double getError() const; // double getError() const;
}; // };
//
#include <gtsam_unstable/nonlinear/FixedLagSmoother.h> // #include <gtsam_unstable/nonlinear/FixedLagSmoother.h>
virtual class FixedLagSmoother { // virtual class FixedLagSmoother {
void print(string s) const; // void print(string s) const;
bool equals(const gtsam::FixedLagSmoother& rhs, double tol) const; // bool equals(const gtsam::FixedLagSmoother& rhs, double tol) const;
//
gtsam::FixedLagSmootherKeyTimestampMap timestamps() const; // gtsam::FixedLagSmootherKeyTimestampMap timestamps() const;
double smootherLag() const; // double smootherLag() const;
//
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps); // gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps);
gtsam::Values calculateEstimate() const; // gtsam::Values calculateEstimate() const;
}; // };
//
#include <gtsam_unstable/nonlinear/BatchFixedLagSmoother.h> // #include <gtsam_unstable/nonlinear/BatchFixedLagSmoother.h>
virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother { // virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
BatchFixedLagSmoother(); // BatchFixedLagSmoother();
BatchFixedLagSmoother(double smootherLag); // BatchFixedLagSmoother(double smootherLag);
BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params); // BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
//
gtsam::LevenbergMarquardtParams params() const; // gtsam::LevenbergMarquardtParams params() const;
}; // };
//
#include <gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h> // #include <gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h>
virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother { // virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
IncrementalFixedLagSmoother(); // IncrementalFixedLagSmoother();
IncrementalFixedLagSmoother(double smootherLag); // IncrementalFixedLagSmoother(double smootherLag);
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); // IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
//
gtsam::ISAM2Params params() const; // gtsam::ISAM2Params params() const;
}; // };
//
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h> // #include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
virtual class ConcurrentFilter { // virtual class ConcurrentFilter {
void print(string s) const; // void print(string s) const;
bool equals(const gtsam::ConcurrentFilter& rhs, double tol) const; // bool equals(const gtsam::ConcurrentFilter& rhs, double tol) const;
}; // };
//
virtual class ConcurrentSmoother { // virtual class ConcurrentSmoother {
void print(string s) const; // void print(string s) const;
bool equals(const gtsam::ConcurrentSmoother& rhs, double tol) const; // bool equals(const gtsam::ConcurrentSmoother& rhs, double tol) const;
}; // };
//
// Synchronize function // // Synchronize function
void synchronize(gtsam::ConcurrentFilter& filter, gtsam::ConcurrentSmoother& smoother); // void synchronize(gtsam::ConcurrentFilter& filter, gtsam::ConcurrentSmoother& smoother);
//
#include <gtsam_unstable/nonlinear/ConcurrentBatchFilter.h> // #include <gtsam_unstable/nonlinear/ConcurrentBatchFilter.h>
class ConcurrentBatchFilterResult { // class ConcurrentBatchFilterResult {
size_t getIterations() const; // size_t getIterations() const;
size_t getLambdas() const; // size_t getLambdas() const;
size_t getNonlinearVariables() const; // size_t getNonlinearVariables() const;
size_t getLinearVariables() const; // size_t getLinearVariables() const;
double getError() const; // double getError() const;
}; // };
//
virtual class ConcurrentBatchFilter : gtsam::ConcurrentFilter { // virtual class ConcurrentBatchFilter : gtsam::ConcurrentFilter {
ConcurrentBatchFilter(); // ConcurrentBatchFilter();
ConcurrentBatchFilter(const gtsam::LevenbergMarquardtParams& parameters); // ConcurrentBatchFilter(const gtsam::LevenbergMarquardtParams& parameters);
//
gtsam::NonlinearFactorGraph getFactors() const; // gtsam::NonlinearFactorGraph getFactors() const;
gtsam::Values getLinearizationPoint() const; // gtsam::Values getLinearizationPoint() const;
gtsam::Ordering getOrdering() const; // gtsam::Ordering getOrdering() const;
gtsam::VectorValues getDelta() const; // gtsam::VectorValues getDelta() const;
//
gtsam::ConcurrentBatchFilterResult update(); // gtsam::ConcurrentBatchFilterResult update();
gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors); // gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors);
gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); // gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyList& keysToMove); // gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyList& keysToMove);
gtsam::Values calculateEstimate() const; // gtsam::Values calculateEstimate() const;
}; // };
//
#include <gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h> // #include <gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h>
class ConcurrentBatchSmootherResult { // class ConcurrentBatchSmootherResult {
size_t getIterations() const; // size_t getIterations() const;
size_t getLambdas() const; // size_t getLambdas() const;
size_t getNonlinearVariables() const; // size_t getNonlinearVariables() const;
size_t getLinearVariables() const; // size_t getLinearVariables() const;
double getError() const; // double getError() const;
}; // };
//
virtual class ConcurrentBatchSmoother : gtsam::ConcurrentSmoother { // virtual class ConcurrentBatchSmoother : gtsam::ConcurrentSmoother {
ConcurrentBatchSmoother(); // ConcurrentBatchSmoother();
ConcurrentBatchSmoother(const gtsam::LevenbergMarquardtParams& parameters); // ConcurrentBatchSmoother(const gtsam::LevenbergMarquardtParams& parameters);
//
gtsam::NonlinearFactorGraph getFactors() const; // gtsam::NonlinearFactorGraph getFactors() const;
gtsam::Values getLinearizationPoint() const; // gtsam::Values getLinearizationPoint() const;
gtsam::Ordering getOrdering() const; // gtsam::Ordering getOrdering() const;
gtsam::VectorValues getDelta() const; // gtsam::VectorValues getDelta() const;
//
gtsam::ConcurrentBatchSmootherResult update(); // gtsam::ConcurrentBatchSmootherResult update();
gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors); // gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors);
gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); // gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
gtsam::Values calculateEstimate() const; // gtsam::Values calculateEstimate() const;
}; // };
//************************************************************************* //*************************************************************************
// slam // slam