Fix broken file

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

View File

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