formatting

release/4.3a0
Frank Dellaert 2012-06-03 03:31:31 +00:00
parent fd8ec0a605
commit 608155851a
1 changed files with 105 additions and 97 deletions

70
gtsam.h
View File

@ -129,9 +129,9 @@ class Rot3 {
static gtsam::Rot3 Rz(double t);
// static gtsam::Rot3 RzRyRx(double x, double y, double z); // FIXME: overloaded functions don't work yet
static gtsam::Rot3 RzRyRx(Vector xyz);
static gtsam::Rot3 yaw (double t); // positive yaw is to right (as in aircraft heading)
static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading)
static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude)
static gtsam::Rot3 roll (double t); // positive roll is to right (increasing yaw in aircraft)
static gtsam::Rot3 roll(double t); // positive roll is to right (increasing yaw in aircraft)
static gtsam::Rot3 ypr(double y, double p, double r);
static gtsam::Rot3 quaternion(double w, double x, double y, double z);
static gtsam::Rot3 rodriguez(Vector v);
@ -228,13 +228,10 @@ class CalibratedCamera {
static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint);
};
//*************************************************************************
// inference
//*************************************************************************
//*************************************************************************
// linear
//*************************************************************************
@ -305,7 +302,8 @@ class GaussianFactor {
class JacobianFactor {
JacobianFactor();
JacobianFactor(Vector b_in);
JacobianFactor(int i1, Matrix A1, Vector b, const gtsam::SharedDiagonal& model);
JacobianFactor(int i1, Matrix A1, Vector b,
const gtsam::SharedDiagonal& model);
JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, Vector b,
const gtsam::SharedDiagonal& model);
JacobianFactor(int i1, Matrix A1, int i2, Matrix A2, int i3, Matrix A3,
@ -361,7 +359,8 @@ class GaussianFactorGraph {
double probPrime(const gtsam::VectorValues& c) const;
// combining
static gtsam::GaussianFactorGraph combine2(const gtsam::GaussianFactorGraph& lfg1,
static gtsam::GaussianFactorGraph combine2(
const gtsam::GaussianFactorGraph& lfg1,
const gtsam::GaussianFactorGraph& lfg2);
void combine(const gtsam::GaussianFactorGraph& lfg);
@ -372,7 +371,8 @@ class GaussianFactorGraph {
};
class GaussianSequentialSolver {
GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph, bool useQR);
GaussianSequentialSolver(const gtsam::GaussianFactorGraph& graph,
bool useQR);
gtsam::GaussianBayesNet* eliminate() const;
gtsam::VectorValues* optimize() const;
gtsam::GaussianFactor* marginalFactor(int j) const;
@ -385,16 +385,16 @@ class KalmanFilter {
gtsam::GaussianDensity* init(Vector x0, Matrix P0);
void print(string s) const;
static int step(gtsam::GaussianDensity* p);
gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, Matrix B, Vector u,
const gtsam::SharedDiagonal& modelQ);
gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, Matrix B, Vector u,
Matrix Q);
gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, Matrix A1, Vector b,
const gtsam::SharedDiagonal& model);
gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, Vector z,
const gtsam::SharedDiagonal& model);
gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, Vector z,
Matrix Q);
gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F,
Matrix B, Vector u, const gtsam::SharedDiagonal& modelQ);
gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F,
Matrix B, Vector u, Matrix Q);
gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0,
Matrix A1, Vector b, const gtsam::SharedDiagonal& model);
gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H,
Vector z, const gtsam::SharedDiagonal& model);
gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H,
Vector z, Matrix Q);
};
//*************************************************************************
@ -425,13 +425,14 @@ class Values {
};
class Marginals {
Marginals(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& solution);
Marginals(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& solution);
void print(string s) const;
Matrix marginalCovariance(size_t variable) const;
Matrix marginalInformation(size_t variable) const;
};
}///\namespace gtsam
} ///\namespace gtsam
//*************************************************************************
// planarSLAM
@ -459,13 +460,17 @@ class Graph {
gtsam::GaussianFactorGraph* linearize(const planarSLAM::Values& values,
const gtsam::Ordering& ordering) const;
void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel);
void addPoseConstraint(int key, const gtsam::Pose2& pose);
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel);
void addBearing(int poseKey, int pointKey, const gtsam::Rot2& bearing, const gtsam::SharedNoiseModel& noiseModel);
void addRange(int poseKey, int pointKey, double range, const gtsam::SharedNoiseModel& noiseModel);
void addBearingRange(int poseKey, int pointKey, const gtsam::Rot2& bearing, double range,
void addPrior(int key, const gtsam::Pose2& pose,
const gtsam::SharedNoiseModel& noiseModel);
void addPoseConstraint(int key, const gtsam::Pose2& pose);
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry,
const gtsam::SharedNoiseModel& noiseModel);
void addBearing(int poseKey, int pointKey, const gtsam::Rot2& bearing,
const gtsam::SharedNoiseModel& noiseModel);
void addRange(int poseKey, int pointKey, double range,
const gtsam::SharedNoiseModel& noiseModel);
void addBearingRange(int poseKey, int pointKey, const gtsam::Rot2& bearing,
double range, const gtsam::SharedNoiseModel& noiseModel);
planarSLAM::Values optimize(const planarSLAM::Values& initialEstimate);
};
@ -473,10 +478,11 @@ class Odometry {
Odometry(int key1, int key2, const gtsam::Pose2& measured,
const gtsam::SharedNoiseModel& model);
void print(string s) const;
gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, const gtsam::Ordering& ordering) const;
gtsam::GaussianFactor* linearize(const planarSLAM::Values& center,
const gtsam::Ordering& ordering) const;
};
}///\namespace planarSLAM
} ///\namespace planarSLAM
//*************************************************************************
// Pose2SLAM
@ -502,14 +508,16 @@ class Graph {
gtsam::GaussianFactorGraph* linearize(const pose2SLAM::Values& values,
const gtsam::Ordering& ordering) const;
void addPrior(int key, const gtsam::Pose2& pose, const gtsam::SharedNoiseModel& noiseModel);
void addPrior(int key, const gtsam::Pose2& pose,
const gtsam::SharedNoiseModel& noiseModel);
void addPoseConstraint(int key, const gtsam::Pose2& pose);
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry, const gtsam::SharedNoiseModel& noiseModel);
void addOdometry(int key1, int key2, const gtsam::Pose2& odometry,
const gtsam::SharedNoiseModel& noiseModel);
pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate) const;
gtsam::Marginals marginals(const pose2SLAM::Values& solution) const;
};
}///\namespace pose2SLAM
} ///\namespace pose2SLAM
//*************************************************************************
// Simulated2D