Update unstable.h file to match upstream

release/4.3a0
Jeremy Aguilon 2019-03-07 14:23:11 -05:00
parent 9a3d517925
commit f4bf0d5b0b
1 changed files with 125 additions and 123 deletions

View File

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