gtsam/gtsam.h

190 lines
5.4 KiB
C
Raw Normal View History

class Point2 {
Point2();
Point2(double x, double y);
void print(string s) const;
double x();
double y();
};
class Point3 {
Point3();
Point3(double x, double y, double z);
Point3(Vector v);
void print(string s) const;
Vector vector() const;
double x();
double y();
double z();
};
2011-10-14 12:43:40 +08:00
class Rot2 {
Rot2();
2011-10-22 00:56:50 +08:00
Rot2(double theta);
void print(string s) const;
bool equals(const Rot2& pose, double tol) const;
double c() const;
double s() const;
2011-10-14 12:43:40 +08:00
};
class Pose2 {
Pose2();
Pose2(double x, double y, double theta);
Pose2(double theta, const Point2& t);
Pose2(const Rot2& r, const Point2& t);
Pose2(Vector v);
void print(string s) const;
bool equals(const Pose2& pose, double tol) const;
double x() const;
double y() const;
double theta() const;
2011-11-04 12:27:55 +08:00
int dim() const;
Pose2* compose_(const Pose2& p2);
Pose2* between_(const Pose2& p2);
2011-11-08 05:16:26 +08:00
Vector localCoordinates(const Pose2& p);
Pose2* retract_(Vector v);
};
class SharedGaussian {
SharedGaussian(Matrix covariance);
2011-11-05 22:26:57 +08:00
void print(string s) const;
};
class SharedDiagonal {
SharedDiagonal(Vector sigmas);
2011-11-05 22:26:57 +08:00
void print(string s) const;
Vector sample() const;
};
class VectorValues {
VectorValues();
2011-11-04 12:27:55 +08:00
VectorValues(int nVars, int varDim);
void print(string s) const;
bool equals(const VectorValues& expected, double tol) const;
2011-11-04 12:27:55 +08:00
int size() const;
void insert(int j, const Vector& value);
};
2011-10-23 03:42:02 +08:00
class GaussianConditional {
2011-11-04 12:27:55 +08:00
GaussianConditional(int key, Vector d, Matrix R, Vector sigmas);
GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S,
2011-10-23 03:42:02 +08:00
Vector sigmas);
2011-11-04 12:27:55 +08:00
GaussianConditional(int key, Vector d, Matrix R, int name1, Matrix S,
int name2, Matrix T, Vector sigmas);
2011-10-23 03:42:02 +08:00
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;
};
2011-10-23 03:42:02 +08:00
class JacobianFactor {
JacobianFactor();
JacobianFactor(Vector b_in);
2011-11-04 12:27:55 +08:00
JacobianFactor(int i1, Matrix A1, Vector b, const SharedDiagonal& model);
JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, Vector b,
2011-10-23 03:42:02 +08:00
const SharedDiagonal& model);
2011-11-04 12:27:55 +08:00
JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, int i3, Matrix A3,
Vector b, const SharedDiagonal& model);
2011-10-23 03:42:02 +08:00
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();
};
2011-10-23 03:42:02 +08:00
class GaussianFactorGraph {
GaussianFactorGraph();
void print(string s) const;
bool equals(const GaussianFactorGraph& lfgraph, double tol) const;
2011-11-04 12:27:55 +08:00
int size() const;
2011-10-23 03:42:02 +08:00
void push_back(GaussianFactor* ptr_f);
double error(const VectorValues& c) const;
double probPrime(const VectorValues& c) const;
void combine(const GaussianFactorGraph& lfg);
2011-11-04 12:27:55 +08:00
Matrix denseJacobian() const;
Matrix denseHessian() const;
2011-10-31 04:38:08 +08:00
Matrix sparseJacobian_() const;
2011-10-23 03:42:02 +08:00
};
class KalmanFilter {
KalmanFilter(Vector x, const SharedDiagonal& model);
void print(string s) const;
Vector mean() const;
Matrix information() const;
Matrix covariance() const;
void predict(Matrix F, Matrix B, Vector u, const SharedDiagonal& model);
2011-11-04 22:10:32 +08:00
void predict2(Matrix A0, Matrix A1, Vector b, const SharedDiagonal& model);
void update(Matrix H, Vector z, const SharedDiagonal& model);
};
2011-10-22 00:56:50 +08:00
class Landmark2 {
Landmark2();
Landmark2(double x, double y);
void print(string s) const;
double x();
double y();
};
2011-11-04 12:27:55 +08:00
class Ordering {
Ordering();
void print(string s) const;
bool equals(const Ordering& ord, double tol) const;
void push_back(string key);
2011-10-22 00:56:50 +08:00
};
class PlanarSLAMValues {
PlanarSLAMValues();
void print(string s) const;
Pose2* pose(int key);
2011-10-22 00:56:50 +08:00
void insertPose(int key, const Pose2& pose);
void insertPoint(int key, const Point2& point);
};
class PlanarSLAMGraph {
PlanarSLAMGraph();
void print(string s) const;
double error(const PlanarSLAMValues& values) const;
Ordering* orderingCOLAMD(const PlanarSLAMValues& values) const;
GaussianFactorGraph* linearize(const PlanarSLAMValues& values,
2011-11-04 12:27:55 +08:00
const Ordering& ordering) const;
void addPrior(int key, const Pose2& pose, const SharedNoiseModel& noiseModel);
void addPoseConstraint(int key, const Pose2& pose);
void addOdometry(int key1, int key2, const Pose2& odometry, const SharedNoiseModel& noiseModel);
void addBearing(int poseKey, int pointKey, const Rot2& bearing, const SharedNoiseModel& noiseModel);
void addRange(int poseKey, int pointKey, double range, const SharedNoiseModel& noiseModel);
void addBearingRange(int poseKey, int pointKey, const Rot2& bearing, double range,
const SharedNoiseModel& noiseModel);
2011-10-23 03:42:02 +08:00
PlanarSLAMValues* optimize_(const PlanarSLAMValues& initialEstimate);
2011-10-22 00:56:50 +08:00
};
2011-11-04 12:27:55 +08:00
class PlanarSLAMOdometry {
PlanarSLAMOdometry(int key1, int key2, const Pose2& measured,
const SharedNoiseModel& model);
void print(string s) const;
GaussianFactor* linearize(const PlanarSLAMValues& center, const Ordering& ordering) const;
2011-11-04 12:27:55 +08:00
};
class GaussianSequentialSolver {
GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR);
GaussianBayesNet* eliminate() const;
VectorValues* optimize() const;
GaussianFactor* marginalFactor(int j) const;
Matrix marginalCovariance(int j) const;
};