55 using namespace gtsam;
58 int main(
int argc,
char* argv[]) {
63 auto noise = noiseModel::Isotropic::Sigma(2, 1.0);
81 for (
size_t i = 0;
i < poses.size(); ++
i) {
83 for (
size_t j = 0;
j < points.size(); ++
j) {
93 Pose3 noise(Rot3::Rodrigues(-0.1, 0.2, 0.25),
Point3(0.05, -0.10, 0.20));
105 auto poseNoise = noiseModel::Diagonal::Sigmas(
106 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
111 noiseModel::Isotropic::Sigma(3, 0.1);
115 Point3 noise(-0.25, 0.20, 0.15);
116 for (
size_t j = 0;
j < points.size(); ++
j) {
118 Point3 initial_lj = points[
j] + noise;
124 isam.
update(graph, initialEstimate);
126 cout <<
"****************************************************" << endl;
127 cout <<
"Frame " <<
i <<
": " << endl;
128 currentEstimate.
print(
"Current estimate: ");
132 initialEstimate.
clear();
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.
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
int main(int argc, char *argv[])
std::vector< gtsam::Point3 > createPoints()
static Point2 measurement(323.0, 240.0)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
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
std::shared_ptr< Cal3_S2 > shared_ptr
NonlinearISAM isam(relinearizeInterval)
The most common 5DOF 3D->2D calibration.
Class compose(const Class &g) const
Reprojection of a LANDMARK to a 2D point.
virtual void resize(size_t size)
Simple example for the structure-from-motion problems.
void insert(Key j, const Value &val)
static const CalibratedCamera camera(kDefaultPose)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
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)