32 using namespace gtsam;
41 int main(
int argc,
char* argv[]) {
47 auto measurementNoise =
48 noiseModel::Isotropic::Sigma(2, 1.0);
58 for (
size_t j = 0;
j < points.size(); ++
j) {
63 for (
size_t i = 0;
i < poses.size(); ++
i) {
74 smartfactor->add(measurement, i);
83 auto noise = noiseModel::Diagonal::Sigmas(
84 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
93 graph.
print(
"Factor Graph:\n");
99 for (
size_t i = 0;
i < poses.size(); ++
i)
100 initialEstimate.
insert(
i, poses[
i].compose(delta));
101 initialEstimate.
print(
"Initial Estimates:\n");
106 result.
print(
"Final results:\n");
112 for (
size_t j = 0;
j < points.size(); ++
j) {
119 boost::optional<Point3>
point = smart->point(result);
121 landmark_result.
insert(
j, *point);
125 landmark_result.
print(
"Landmark results:\n");
126 cout <<
"final error: " << graph.
error(result) << endl;
127 cout <<
"number of iterations: " << optimizer.
iterations() << endl;
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
void insert(Key j, const Value &val)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
std::vector< gtsam::Point3 > createPoints()
int main(int argc, char *argv[])
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
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)
Simple example for the structure-from-motion problems.
PinholePose< Cal3_S2 > Camera
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
size_t iterations() const
return number of iterations in current optimizer state