39 using namespace gtsam;
40 using namespace noiseModel;
43 int main(
int argc,
char* argv[]) {
45 Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
68 for (
size_t i = 0;
i < poses.size(); ++
i) {
71 for (
size_t j = 0;
j < points.size(); ++
j) {
88 for (
size_t i = 0;
i < poses.size(); ++
i)
90 for (
size_t j = 0;
j < points.size(); ++
j)
92 cout <<
"initial error = " << graph.
error(initial) << endl;
96 cout <<
"final error = " << graph.
error(result) << endl;
Expression< Point3 > Point3_
int main(int argc, char *argv[])
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
void insert(Key j, const Value &val)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
T compose(const T &t1, const T &t2)
std::vector< gtsam::Point3 > createPoints()
Factor graph that supports adding ExpressionFactors directly.
boost::shared_ptr< Diagonal > shared_ptr
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.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
boost::shared_ptr< Isotropic > shared_ptr
void addExpressionFactor(const Expression< T > &h, const T &z, const SharedNoiseModel &R)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)