29 using namespace gtsam;
31 int main(
int argc,
char *argv[]) {
36 Values::shared_ptr solution;
40 boost::tie(g, solution) =
load2D(inputFile, model);
45 Values::ConstFiltered<Pose2> poses = solution->filter<
Pose2>();
47 for(
const Values::ConstFiltered<Pose2>::KeyValuePair& it: poses)
48 initial.
insert(it.key, it.value.retract(sampler.sampleNewModel(noise)));
52 noiseModel::Diagonal::Sigmas(
Vector3(1
e-6, 1
e-6, 1
e-8));
53 g->addPrior(0,
Pose2(), priorModel);
56 for (
size_t i = 0;
i < trials;
i++) {
virtual const Values & optimize()
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
void g(const string &key, int i)
string findExampleDataFile(const string &name)
Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers:
boost::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
sampling from a NoiseModel
boost::shared_ptr< Diagonal > shared_ptr
noiseModel::Diagonal::shared_ptr SharedDiagonal
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
void tictoc_finishedIteration_()
int main(int argc, char *argv[])
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
utility functions for loading datasets