formatting
parent
fd8ec0a605
commit
608155851a
60
gtsam.h
60
gtsam.h
|
@ -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,7 +425,8 @@ 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;
|
||||
|
@ -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,7 +478,8 @@ 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
|
||||
|
@ -502,9 +508,11 @@ 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;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue