small wrapper updates
parent
d90dca7fab
commit
158a620eba
|
@ -33,13 +33,13 @@ class IndexPair {
|
|||
size_t j() const;
|
||||
};
|
||||
|
||||
// template<KEY = {gtsam::IndexPair}>
|
||||
// class DSFMap {
|
||||
// DSFMap();
|
||||
// KEY find(const KEY& key) const;
|
||||
// void merge(const KEY& x, const KEY& y);
|
||||
// std::map<KEY, Set> sets();
|
||||
// };
|
||||
template<KEY = {gtsam::IndexPair}>
|
||||
class DSFMap {
|
||||
DSFMap();
|
||||
KEY find(const KEY& key) const;
|
||||
void merge(const KEY& x, const KEY& y);
|
||||
std::map<KEY, Set> sets();
|
||||
};
|
||||
|
||||
class IndexPairSet {
|
||||
IndexPairSet();
|
||||
|
@ -81,13 +81,6 @@ class IndexPairSetMap {
|
|||
gtsam::IndexPairSet at(gtsam::IndexPair& key);
|
||||
};
|
||||
|
||||
class DSFMapIndexPair {
|
||||
DSFMapIndexPair();
|
||||
gtsam::IndexPair find(const gtsam::IndexPair& key) const;
|
||||
void merge(const gtsam::IndexPair& x, const gtsam::IndexPair& y);
|
||||
gtsam::IndexPairSetMap sets();
|
||||
};
|
||||
|
||||
#include <gtsam/base/Matrix.h>
|
||||
bool linear_independent(Matrix A, Matrix B, double tol);
|
||||
|
||||
|
|
|
@ -572,8 +572,8 @@ virtual class GncOptimizer {
|
|||
gtsam::Values optimize();
|
||||
};
|
||||
|
||||
typedef gtsam::GncOptimizer<gtsam::GncParams<gtsam::GaussNewtonParams> > GncGaussNewtonOptimizer;
|
||||
typedef gtsam::GncOptimizer<gtsam::GncParams<gtsam::LevenbergMarquardtParams> > GncLMOptimizer;
|
||||
typedef gtsam::GncOptimizer<gtsam::GncParams<gtsam::GaussNewtonParams>> GncGaussNewtonOptimizer;
|
||||
typedef gtsam::GncOptimizer<gtsam::GncParams<gtsam::LevenbergMarquardtParams>> GncLMOptimizer;
|
||||
|
||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer {
|
||||
|
|
Loading…
Reference in New Issue