28 using namespace gtsam;
37 int main(
int argc,
char* argv[]) {
42 auto measurementNoise =
43 noiseModel::Isotropic::Sigma(2, 1.0);
53 for (
size_t j = 0;
j < points.size(); ++
j) {
58 for (
size_t i = 0;
i < poses.size(); ++
i) {
64 smartfactor->add(measurement, i);
73 auto noise = noiseModel::Diagonal::Sigmas(
74 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
83 for (
size_t i = 0;
i < poses.size(); ++
i)
84 initialEstimate.
insert(
i, poses[
i].compose(delta));
96 std::make_shared<PCGSolverParameters>();
97 pcg->preconditioner_ =
98 std::make_shared<BlockJacobiPreconditionerParameters>();
100 pcg->setEpsilon_abs(1
e-10);
101 pcg->setEpsilon_rel(1
e-10);
108 result.
print(
"Final results:\n");
110 for (
size_t j = 0;
j < points.size(); ++
j) {
111 auto smart = std::dynamic_pointer_cast<
SmartFactor>(graph[
j]);
113 std::optional<Point3>
point = smart->point(result);
115 landmark_result.
insert(
j, *point);
119 landmark_result.
print(
"Landmark results:\n");
120 cout <<
"final error: " << graph.
error(result) << endl;
121 cout <<
"number of iterations: " << optimizer.
iterations() << endl;
PinholePose< Cal3_S2 > Camera
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
size_t iterations() const
return number of iterations in current optimizer state
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
std::vector< gtsam::Point3 > createPoints()
static Point2 measurement(323.0, 240.0)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
std::shared_ptr< Cal3_S2 > shared_ptr
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
IterativeOptimizationParameters::shared_ptr iterativeParams
The container for iterativeOptimization parameters. used in CG Solvers.
double error(const Values &values) const
std::shared_ptr< PCGSolverParameters > shared_ptr
static ConjugateGradientParameters parameters
Simple example for the structure-from-motion problems.
void insert(Key j, const Value &val)
int main(int argc, char *argv[])
static const CalibratedCamera camera(kDefaultPose)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
size_t maxIterations
The maximum iterations to stop iterating (default 100)
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), const gtsam::Pose3 &delta=gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4, 0), gtsam::Point3(sin(M_PI/4) *30, 0, 30 *(1-sin(M_PI/4)))), int steps=8)