55 using namespace gtsam;
58 int main(
int argc,
char* argv[]) {
63 auto measurementNoise =
64 noiseModel::Isotropic::Sigma(2, 1.0);
76 auto poseNoise = noiseModel::Diagonal::Sigmas(
77 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
83 for (
size_t i = 0;
i < poses.size(); ++
i) {
85 for (
size_t j = 0;
j < points.size(); ++
j) {
97 auto pointNoise = noiseModel::Isotropic::Sigma(3, 0.1);
100 graph.
print(
"Factor Graph:\n");
105 for (
size_t i = 0;
i < poses.size(); ++
i) {
106 auto corrupted_pose = poses[
i].compose(
107 Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25),
Point3(0.05, -0.10, 0.20)));
109 Symbol(
'x',
i), corrupted_pose);
111 for (
size_t j = 0;
j < points.size(); ++
j) {
112 Point3 corrupted_point = points[
j] +
Point3(-0.25, 0.20, 0.15);
113 initialEstimate.
insert<Point3>(
Symbol(
'l',
j), corrupted_point);
115 initialEstimate.
print(
"Initial Estimates:\n");
119 result.
print(
"Final results:\n");
120 cout <<
"initial error = " << graph.
error(initialEstimate) << endl;
121 cout <<
"final error = " << graph.
error(result) << endl;
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
int main(int argc, char *argv[])
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
std::vector< gtsam::Point3 > createPoints()
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Basic bearing factor from 2D measurement.
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.
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
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