unbroke a number of classes in linear, testing them with gtsam_experimental/matlab code

release/4.3a0
Frank Dellaert 2011-10-21 05:07:35 +00:00
parent ad4299e468
commit 168ad81230
2 changed files with 96 additions and 82 deletions

View File

@ -1,15 +1,6 @@
// These are considered to be broken and will be added back as they start working
// It's assumed that there have been interface changes that might break this
class SharedGaussian {
SharedGaussian(Matrix covariance);
SharedGaussian(Vector sigmas);
};
class SharedDiagonal {
SharedDiagonal(Vector sigmas);
};
class Ordering {
Ordering();
void print(string s) const;
@ -17,55 +8,11 @@ class Ordering {
void push_back(string s);
};
class VectorValues {
VectorValues();
VectorValues(size_t nVars, size_t varDim);
void print(string s) const;
bool equals(const VectorValues& expected, double tol) const;
size_t size() const;
};
class GaussianFactor {
void print(string s) const;
bool equals(const GaussianFactor& lf, double tol) const;
bool empty() const;
Vector getb() const;
double error(const VectorValues& c) const;
};
class GaussianFactorSet {
GaussianFactorSet();
void push_back(GaussianFactor* factor);
};
class GaussianConditional {
GaussianConditional();
void print(string s) const;
bool equals(const GaussianConditional &cg, double tol) const;
Vector solve(const VectorValues& x);
};
class GaussianBayesNet {
GaussianBayesNet();
void print(string s) const;
bool equals(const GaussianBayesNet& cbn, double tol) const;
void push_back(GaussianConditional* conditional);
void push_front(GaussianConditional* conditional);
};
class GaussianFactorGraph {
GaussianFactorGraph();
void print(string s) const;
bool equals(const GaussianFactorGraph& lfgraph, double tol) const;
size_t size() const;
void push_back(GaussianFactor* ptr_f);
double error(const VectorValues& c) const;
double probPrime(const VectorValues& c) const;
void combine(const GaussianFactorGraph& lfg);
};
class Simulated2DValues {
Simulated2DValues();
void print(string s) const;

75
gtsam.h
View File

@ -33,9 +33,76 @@ class Pose2 {
double y() const;
double theta() const;
size_t dim() const;
Pose2 expmap(Vector v) const;
Vector logmap(const Pose2& pose) const;
Point2 t() const;
Rot2 r() const;
};
class SharedGaussian {
SharedGaussian(Matrix covariance);
SharedGaussian(Vector sigmas);
};
class SharedDiagonal {
SharedDiagonal(Vector sigmas);
};
class VectorValues {
VectorValues();
VectorValues(size_t nVars, size_t varDim);
void print(string s) const;
bool equals(const VectorValues& expected, double tol) const;
size_t size() const;
void reserve(size_t nVars, size_t totalDims);
size_t push_back_preallocated(Vector vector);
};
class GaussianConditional {
GaussianConditional(size_t key, Vector d, Matrix R, Vector sigmas);
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
Vector sigmas);
GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S,
size_t name2, Matrix T, Vector sigmas);
void print(string s) const;
bool equals(const GaussianConditional &cg, double tol) const;
};
class GaussianBayesNet {
GaussianBayesNet();
void print(string s) const;
bool equals(const GaussianBayesNet& cbn, double tol) const;
void push_back(GaussianConditional* conditional);
void push_front(GaussianConditional* conditional);
};
class GaussianFactor {
void print(string s) const;
bool equals(const GaussianFactor& lf, double tol) const;
double error(const VectorValues& c) const;
};
class JacobianFactor {
JacobianFactor();
JacobianFactor(Vector b_in);
JacobianFactor(size_t i1, Matrix A1, Vector b, const SharedDiagonal& model);
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b,
const SharedDiagonal& model);
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3,
Matrix A3, Vector b, const SharedDiagonal& model);
void print(string s) const;
bool equals(const GaussianFactor& lf, double tol) const;
bool empty() const;
Vector getb() const;
double error(const VectorValues& c) const;
GaussianConditional* eliminateFirst();
};
class GaussianFactorGraph {
GaussianFactorGraph();
void print(string s) const;
bool equals(const GaussianFactorGraph& lfgraph, double tol) const;
size_t size() const;
void push_back(GaussianFactor* ptr_f);
double error(const VectorValues& c) const;
double probPrime(const VectorValues& c) const;
void combine(const GaussianFactorGraph& lfg);
};