56 using namespace gtsam;
62 int main(
int argc,
char *argv[]) {
64 auto K = std::make_shared<Cal3Fisheye>(
65 278.66, 278.48, 0.0, 319.75, 241.96, -0.013721808247486035,
66 0.020727425669427896, -0.012786476702685545, 0.0025242267320687625);
69 auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
82 auto posePrior = noiseModel::Diagonal::Sigmas(
83 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
87 auto pointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
92 static const Point3 kDeltaPoint(-0.25, 0.20, 0.15);
93 for (
size_t j = 0;
j < points.
size(); ++
j)
97 for (
size_t i = 0;
i < poses.
size(); ++
i) {
99 for (
size_t j = 0;
j < points.
size(); ++
j) {
108 static const Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
109 Point3(0.05, -0.10, 0.20));
110 initialEstimate.
insert(
X(
i), poses[
i] * kDeltaPose);
117 std::cout <<
"Optimizing the factor graph" << std::endl;
120 std::cout <<
"Optimization complete" << std::endl;
122 std::cout <<
"initial error=" << graph.
error(initialEstimate) << std::endl;
123 std::cout <<
"final error=" << graph.
error(result) << std::endl;
125 graph.
saveGraph(
"examples/vio_batch.dot", result);
virtual const Values & optimize()
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
int main(int argc, char *argv[])
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
static const SmartProjectionParams params
std::vector< gtsam::Point3 > createPoints()
static Point2 measurement(323.0, 240.0)
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
void setVerbosity(const std::string &src)
void saveGraph(const std::string &filename, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const
output to file with graphviz format, with Values/extra options.
double error(const Values &values) const
Reprojection of a LANDMARK to a 2D point.
Simple example for the structure-from-motion problems.
void insert(Key j, const Value &val)
Calibration of a fisheye camera.
static const CalibratedCamera camera(kDefaultPose)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
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)