46 #include <gtsam/config.h> 48 #include <boost/archive/binary_iarchive.hpp> 49 #include <boost/archive/binary_oarchive.hpp> 50 #include <boost/program_options.hpp> 51 #include <boost/range/algorithm/set_algorithm.hpp> 52 #include <boost/range/adaptor/reversed.hpp> 53 #include <boost/serialization/export.hpp> 60 #include <tbb/task_arena.h> 61 #include <tbb/task_group.h> 65 using namespace gtsam;
67 namespace po = boost::program_options;
82 for(
const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
83 graph_dim += (
int)nlf->dim();
85 double dof = double(graph_dim) - double(config.
dim());
86 return 2. * graph.error(config) / dof;
117 int main(
int argc,
char *argv[]) {
119 po::options_description desc(
"Available options");
121 (
"help",
"Print help message")
122 (
"write-solution,o", po::value<string>(&
outputFile)->default_value(
""),
"Write graph and solution to the specified file")
123 (
"read-solution,i", po::value<string>(&
inputFile)->default_value(
""),
"Read graph and solution from the specified file")
124 (
"dataset,d", po::value<string>(&
datasetName)->default_value(
""),
"Read a dataset file (if and only if --incremental is used)")
125 (
"first-step,f", po::value<int>(&
firstStep)->default_value(0),
"First step to process from the dataset file")
126 (
"last-step,l", po::value<int>(&
lastStep)->default_value(-1),
"Last step to process, or -1 to process until the end of the dataset")
127 (
"threads", po::value<int>(&
nThreads)->default_value(-1),
"Number of threads, or -1 to use all processors")
128 (
"relinSkip", po::value<int>(&
relinSkip)->default_value(10),
"Fluid relinearization check every arg steps")
129 (
"incremental",
"Run in incremental mode using ISAM2 (default)")
130 (
"dogleg",
"When in incremental mode, solve with Dogleg instead of Gauss-Newton in iSAM2")
131 (
"batch",
"Run in batch mode, requires an initialization from --read-solution")
132 (
"compare", po::value<vector<string> >()->multitoken(),
"Compare two solution files")
133 (
"perturb", po::value<double>(&
perturbationNoise),
"Perturb a solution file with the specified noise")
134 (
"stats",
"Gather factorization statistics about the dataset, writes text-file histograms")
136 po::variables_map vm;
137 po::store(po::command_line_parser(argc, argv).
options(desc).
run(), vm);
140 batch = (vm.count(
"batch") > 0);
141 compare = (vm.count(
"compare") > 0);
142 perturb = (vm.count(
"perturb") > 0);
143 stats = (vm.count(
"stats") > 0);
145 incremental = (vm.count(
"incremental") > 0 || modesSpecified == 0);
146 dogleg = (vm.count(
"dogleg") > 0);
148 const vector<string>& compareFiles = vm[
"compare"].as<vector<string> >();
149 if(compareFiles.size() != 2) {
150 cout <<
"Must specify two files with --compare";
157 if(modesSpecified > 1) {
158 cout <<
"Only one of --incremental, --batch, --compare, --perturb, and --stats may be specified\n" << desc << endl;
162 cout <<
"In incremental and batch modes, a dataset must be specified\n" << desc << endl;
166 cout <<
"A dataset may only be specified in incremental or batch modes\n" << desc << endl;
170 cout <<
"In batch model, an input file must be specified\n" << desc << endl;
174 cout <<
"In perturb mode, specify input and output files\n" << desc << endl;
178 cout <<
"In stats mode, specify dataset and input file\n" << desc << endl;
185 cout <<
"Reading input file " <<
inputFile << endl;
186 std::ifstream readerStream(
inputFile.c_str(), ios::binary);
187 boost::archive::binary_iarchive
reader(readerStream);
197 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>
data =
199 datasetMeasurements = *data.first;
200 }
catch(std::exception&
e) {
201 cout << e.what() << endl;
207 tbb::task_arena arena;
210 cout <<
"Using " <<
nThreads <<
" threads" << endl;
213 cout <<
"Using threads for all processors" << endl;
216 std::cout <<
"GTSAM is not compiled with TBB, so threading is disabled and the --threads option cannot be used." << endl;
255 cout <<
"Looking for first measurement from step " <<
firstStep << endl;
256 size_t nextMeasurement = 0;
257 bool havePreviousPose =
false;
259 while(nextMeasurement < datasetMeasurements.
size())
272 havePreviousPose =
true;
280 if(nextMeasurement == datasetMeasurements.
size()) {
281 cout <<
"The supplied first step is past the end of the dataset" << endl;
286 if(!havePreviousPose) {
287 cout <<
"Looks like " << firstPose <<
" is the first time step, so adding a prior on it" << endl;
291 newFactors.
addPrior(firstPose,
Pose(), noiseModel::Unit::Create(3));
294 isam2.
update(newFactors, newVariables);
297 cout <<
"Playing forward time steps..." << endl;
299 for (
size_t step = firstPose;
307 gttic_(Collect_measurements);
308 while(nextMeasurement < datasetMeasurements.
size()) {
316 if(factor->key1() >
step || factor->key2() >
step)
320 if(factor->key1() !=
step && factor->key2() !=
step)
321 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
325 const auto&
measured = factor->measured();
328 if(factor->key1() > factor->key2()) {
329 if(!newVariables.
exists(factor->key1())) {
334 newVariables.
insert(factor->key1(), prevPose *
measured.inverse());
338 if(!newVariables.
exists(factor->key2())) {
351 Key poseKey = factor->keys()[0], lmKey = factor->keys()[1];
355 throw runtime_error(
"Problem in data file, out-of-sequence measurements");
368 const auto&
measured = factor->measured();
370 double measuredRange = measured.
range();
371 newVariables.
insert(lmKey,
377 throw std::runtime_error(
"Unknown factor type read from data file");
381 gttoc_(Collect_measurements);
386 isam2.
update(newFactors, newVariables);
388 }
catch(std::exception&
e) {
389 cout << e.what() << endl;
393 if((
step - firstPose) % 1000 == 0) {
398 cout <<
"chi2 = " << chi2 << endl;
400 }
catch(std::exception& e) {
401 cout << e.what() << endl;
408 if((
step - firstPose) % 1000 == 0) {
409 cout <<
"Step " <<
step << endl;
417 cout <<
"Writing output file " <<
outputFile << endl;
418 std::ofstream writerStream(
outputFile.c_str(), ios::binary);
419 boost::archive::binary_oarchive writer(writerStream);
422 }
catch(std::exception&
e) {
423 cout << e.what() << endl;
471 cout <<
"Creating batch optimizer..." << endl;
474 measurements.
addPrior(0,
Pose(), noiseModel::Unit::Create(3));
483 lastError = optimizer.
error();
484 gttic_(Iterate_optimizer);
486 gttoc_(Iterate_optimizer);
487 cout <<
"Error: " << lastError <<
" -> " << optimizer.
error() << endl;
490 cout <<
"chi2 = " << chi2 << endl;
502 cout <<
"Writing output file " <<
outputFile << endl;
503 std::ofstream writerStream(
outputFile.c_str(), ios::binary);
504 boost::archive::binary_oarchive writer(writerStream);
505 writer << optimizer.
values();
506 }
catch(std::exception&
e) {
507 cout << e.what() << endl;
518 cout <<
"Reading solution file " <<
compareFile1 << endl;
520 std::ifstream readerStream(
compareFile1.c_str(), ios::binary);
521 boost::archive::binary_iarchive
reader(readerStream);
525 cout <<
"Reading solution file " <<
compareFile2 << endl;
527 std::ifstream readerStream(
compareFile2.c_str(), ios::binary);
528 boost::archive::binary_iarchive
reader(readerStream);
533 cout <<
"Comparing solutions..." << endl;
535 br::set_symmetric_difference(soln1.
keys(), soln2.
keys(), std::back_inserter(missingKeys));
536 if(!missingKeys.empty()) {
537 cout <<
" Keys unique to one solution file: ";
538 for(
size_t i = 0;
i < missingKeys.size(); ++
i) {
540 if(i != missingKeys.size() - 1)
546 br::set_intersection(soln1.
keys(), soln2.
keys(), std::back_inserter(commonKeys));
547 double maxDiff = 0.0;
548 for(
Key j: commonKeys)
549 maxDiff =
std::max(maxDiff, soln1.
at(
j).localCoordinates_(soln2.
at(
j)).norm());
550 cout <<
" Maximum solution difference (norm of logmap): " << maxDiff << endl;
562 for(
const Values::KeyValuePair key_val: initial)
564 Vector noisev(key_val.value.dim());
566 noisev(
i) = normal(rng);
567 noise.
insert(key_val.key, noisev);
573 cout <<
"Writing output file " <<
outputFile << endl;
574 std::ofstream writerStream(
outputFile.c_str(), ios::binary);
575 boost::archive::binary_oarchive writer(writerStream);
577 }
catch(std::exception&
e) {
578 cout << e.what() << endl;
587 cout <<
"Gathering statistics..." << endl;
594 cout <<
"Writing SolverComparer_Stats_problemSizeHistogram.txt..." << endl;
595 file.open(
"SolverComparer_Stats_problemSizeHistogram.txt");
599 cout <<
"Writing SolverComparer_Stats_numberOfChildrenHistogram.txt..." << endl;
600 file.open(
"SolverComparer_Stats_numberOfChildrenHistogram.txt");
604 cout <<
"Writing SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt..." << endl;
605 file.open(
"SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt");
def step(data, isam, result, truth, currPoseIndex)
Histogram problemSizeHistogram
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
boost::shared_ptr< This > shared_ptr
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)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Struct to store gathered statistics about a forest.
Values retract(const VectorValues &delta) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Histogram problemSizeOfSecondLargestChildHistogram
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
string findExampleDataFile(const string &name)
const Symbol key1('v', 1)
double errorTol
The maximum total error to stop iterating (default 0.0)
Values calculateEstimate() const
boost::shared_ptr< BetweenFactor > shared_ptr
const GaussNewtonParams & params() const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
BearingRangeFactor< Pose, Point2 > BR
const ValueType at(Key j) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Histogram numberOfChildrenHistogram
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
const Values & values() const
return values in current optimizer state
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t * options
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
boost::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
OptimizationParams optimizationParams
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
NoiseModelFactor2< Pose, Pose > NM2
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
GaussianFactorGraph::shared_ptr iterate() override
NonlinearFactorGraph datasetMeasurements
const Symbol key2('v', 2)
bool enablePartialRelinearizationCheck
double chi2_red(const gtsam::NonlinearFactorGraph &graph, const gtsam::Values &config)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
A class for computing marginals in a NonlinearFactorGraph.
void tictoc_finishedIteration_()
const NonlinearFactorGraph & getFactorsUnsafe() const
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
void run(Expr &expr, Dev &dev)
iterator insert(const std::pair< Key, Vector > &key_value)
ForestStatistics GatherStatistics(const FOREST &forest)
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
int main(int argc, char *argv[])
const Values & getLinearizationPoint() const
Access the current linearization point.
NoiseModelFactor1< Pose > NM1