SolverComparer.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8 * See LICENSE for the license information
9 * -------------------------------------------------------------------------- */
10 
36 #include <gtsam/slam/dataset.h>
37 #include <gtsam/geometry/Pose2.h>
38 #include <gtsam/nonlinear/ISAM2.h>
43 #include <gtsam/inference/Symbol.h>
44 #include <gtsam/base/timing.h>
46 #include <gtsam/config.h> // for GTSAM_USE_TBB
47 
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>
54 
55 #include <fstream>
56 #include <iostream>
57 #include <random>
58 
59 #ifdef GTSAM_USE_TBB
60 #include <tbb/task_arena.h> // tbb::task_arena
61 #include <tbb/task_group.h> // tbb::task_group
62 #endif
63 
64 using namespace std;
65 using namespace gtsam;
66 using namespace gtsam::symbol_shorthand;
67 namespace po = boost::program_options;
68 namespace br = boost::range;
69 
70 typedef Pose2 Pose;
71 
75 
77  // Compute degrees of freedom (observations - variables)
78  // In ocaml, +1 was added to the observations to account for the prior, but
79  // the factor graph already includes a factor for the prior/equality constraint.
80  // double dof = graph.size() - config.size();
81  int graph_dim = 0;
82  for(const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
83  graph_dim += (int)nlf->dim();
84  }
85  double dof = double(graph_dim) - double(config.dim()); // kaess: changed to dim
86  return 2. * graph.error(config) / dof; // kaess: added factor 2, graph.error returns half of actual error
87 }
88 
89 // Global variables (these are only set once at program startup and never modified after)
90 string outputFile;
91 string inputFile;
92 string datasetName;
98 bool dogleg;
99 bool batch;
100 bool compare;
101 bool perturb;
102 bool stats;
105 
108 
109 // Run functions for each mode
110 void runIncremental();
111 void runBatch();
112 void runCompare();
113 void runPerturb();
114 void runStats();
115 
116 /* ************************************************************************* */
117 int main(int argc, char *argv[]) {
118 
119  po::options_description desc("Available options");
120  desc.add_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")
135  ;
136  po::variables_map vm;
137  po::store(po::command_line_parser(argc, argv).options(desc).run(), vm);
138  po::notify(vm);
139 
140  batch = (vm.count("batch") > 0);
141  compare = (vm.count("compare") > 0);
142  perturb = (vm.count("perturb") > 0);
143  stats = (vm.count("stats") > 0);
144  const int modesSpecified = int(batch) + int(compare) + int(perturb) + int(stats);
145  incremental = (vm.count("incremental") > 0 || modesSpecified == 0);
146  dogleg = (vm.count("dogleg") > 0);
147  if(compare) {
148  const vector<string>& compareFiles = vm["compare"].as<vector<string> >();
149  if(compareFiles.size() != 2) {
150  cout << "Must specify two files with --compare";
151  exit(1);
152  }
153  compareFile1 = compareFiles[0];
154  compareFile2 = compareFiles[1];
155  }
156 
157  if(modesSpecified > 1) {
158  cout << "Only one of --incremental, --batch, --compare, --perturb, and --stats may be specified\n" << desc << endl;
159  exit(1);
160  }
161  if((incremental || batch) && datasetName.empty()) {
162  cout << "In incremental and batch modes, a dataset must be specified\n" << desc << endl;
163  exit(1);
164  }
165  if(!(incremental || batch || stats) && !datasetName.empty()) {
166  cout << "A dataset may only be specified in incremental or batch modes\n" << desc << endl;
167  exit(1);
168  }
169  if(batch && inputFile.empty()) {
170  cout << "In batch model, an input file must be specified\n" << desc << endl;
171  exit(1);
172  }
173  if(perturb && (inputFile.empty() || outputFile.empty())) {
174  cout << "In perturb mode, specify input and output files\n" << desc << endl;
175  exit(1);
176  }
177  if(stats && (datasetName.empty() || inputFile.empty())) {
178  cout << "In stats mode, specify dataset and input file\n" << desc << endl;
179  exit(1);
180  }
181 
182  // Read input file
183  if(!inputFile.empty())
184  {
185  cout << "Reading input file " << inputFile << endl;
186  std::ifstream readerStream(inputFile.c_str(), ios::binary);
187  boost::archive::binary_iarchive reader(readerStream);
188  reader >> initial;
189  }
190 
191  // Read dataset
192  if(!datasetName.empty())
193  {
194  cout << "Loading dataset " << datasetName << endl;
195  try {
196  string datasetFile = findExampleDataFile(datasetName);
197  std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data =
198  load2D(datasetFile);
199  datasetMeasurements = *data.first;
200  } catch(std::exception& e) {
201  cout << e.what() << endl;
202  exit(1);
203  }
204  }
205 
206 #ifdef GTSAM_USE_TBB
207  tbb::task_arena arena;
208  tbb::task_group tg;
209  if(nThreads > 0) {
210  cout << "Using " << nThreads << " threads" << endl;
211  arena.initialize(nThreads);
212  } else
213  cout << "Using threads for all processors" << endl;
214 #else
215  if(nThreads > 0) {
216  std::cout << "GTSAM is not compiled with TBB, so threading is disabled and the --threads option cannot be used." << endl;
217  exit(1);
218  }
219 #endif
220 
221 #ifdef GTSAM_USE_TBB
222  arena.execute([&]{
223  tg.run_and_wait([&]{
224 #endif
225  // Run mode
226  if(incremental)
227  runIncremental();
228  else if(batch)
229  runBatch();
230  else if(compare)
231  runCompare();
232  else if(perturb)
233  runPerturb();
234  else if(stats)
235  runStats();
236 #ifdef GTSAM_USE_TBB
237  });
238  });
239 #endif
240 
241  return 0;
242 }
243 
244 /* ************************************************************************* */
246 {
248  if(dogleg)
250  params.relinearizeSkip = relinSkip;
251  params.enablePartialRelinearizationCheck = true;
252  ISAM2 isam2(params);
253 
254  // Look for the first measurement to use
255  cout << "Looking for first measurement from step " << firstStep << endl;
256  size_t nextMeasurement = 0;
257  bool havePreviousPose = false;
258  Key firstPose = 0;
259  while(nextMeasurement < datasetMeasurements.size())
260  {
262  boost::dynamic_pointer_cast<BetweenFactor<Pose> >(datasetMeasurements[nextMeasurement]))
263  {
264  Key key1 = factor->key1(), key2 = factor->key2();
265  if(((int)key1 >= firstStep && key1 < key2) || ((int)key2 >= firstStep && key2 < key1)) {
266  // We found an odometry starting at firstStep
267  firstPose = std::min(key1, key2);
268  break;
269  }
270  if(((int)key2 >= firstStep && key1 < key2) || ((int)key1 >= firstStep && key2 < key1)) {
271  // We found an odometry joining firstStep with a previous pose
272  havePreviousPose = true;
273  firstPose = std::max(key1, key2);
274  break;
275  }
276  }
277  ++ nextMeasurement;
278  }
279 
280  if(nextMeasurement == datasetMeasurements.size()) {
281  cout << "The supplied first step is past the end of the dataset" << endl;
282  exit(1);
283  }
284 
285  // If we didn't find an odometry linking to a previous pose, create a first pose and a prior
286  if(!havePreviousPose) {
287  cout << "Looks like " << firstPose << " is the first time step, so adding a prior on it" << endl;
288  NonlinearFactorGraph newFactors;
289  Values newVariables;
290 
291  newFactors.addPrior(firstPose, Pose(), noiseModel::Unit::Create(3));
292  newVariables.insert(firstPose, Pose());
293 
294  isam2.update(newFactors, newVariables);
295  }
296 
297  cout << "Playing forward time steps..." << endl;
298 
299  for (size_t step = firstPose;
300  nextMeasurement < datasetMeasurements.size() && (lastStep == -1 || (int)step <= lastStep);
301  ++step)
302  {
303  Values newVariables;
304  NonlinearFactorGraph newFactors;
305 
306  // Collect measurements and new variables for the current step
307  gttic_(Collect_measurements);
308  while(nextMeasurement < datasetMeasurements.size()) {
309 
310  NonlinearFactor::shared_ptr measurementf = datasetMeasurements[nextMeasurement];
311 
313  boost::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf))
314  {
315  // Stop collecting measurements that are for future steps
316  if(factor->key1() > step || factor->key2() > step)
317  break;
318 
319  // Require that one of the nodes is the current one
320  if(factor->key1() != step && factor->key2() != step)
321  throw runtime_error("Problem in data file, out-of-sequence measurements");
322 
323  // Add a new factor
324  newFactors.push_back(factor);
325  const auto& measured = factor->measured();
326 
327  // Initialize the new variable
328  if(factor->key1() > factor->key2()) {
329  if(!newVariables.exists(factor->key1())) { // Only need to check newVariables since loop closures come after odometry
330  if(step == 1)
331  newVariables.insert(factor->key1(), measured.inverse());
332  else {
333  Pose prevPose = isam2.calculateEstimate<Pose>(factor->key2());
334  newVariables.insert(factor->key1(), prevPose * measured.inverse());
335  }
336  }
337  } else {
338  if(!newVariables.exists(factor->key2())) { // Only need to check newVariables since loop closures come after odometry
339  if(step == 1)
340  newVariables.insert(factor->key2(), measured);
341  else {
342  Pose prevPose = isam2.calculateEstimate<Pose>(factor->key1());
343  newVariables.insert(factor->key2(), prevPose * measured);
344  }
345  }
346  }
347  }
349  boost::dynamic_pointer_cast<BearingRangeFactor<Pose, Point2> >(measurementf))
350  {
351  Key poseKey = factor->keys()[0], lmKey = factor->keys()[1];
352 
353  // Stop collecting measurements that are for future steps
354  if(poseKey > step)
355  throw runtime_error("Problem in data file, out-of-sequence measurements");
356 
357  // Add new factor
358  newFactors.push_back(factor);
359 
360  // Initialize new landmark
361  if(!isam2.getLinearizationPoint().exists(lmKey))
362  {
363  Pose pose;
364  if(isam2.getLinearizationPoint().exists(poseKey))
365  pose = isam2.calculateEstimate<Pose>(poseKey);
366  else
367  pose = newVariables.at<Pose>(poseKey);
368  const auto& measured = factor->measured();
369  Rot2 measuredBearing = measured.bearing();
370  double measuredRange = measured.range();
371  newVariables.insert(lmKey,
372  pose.transformFrom(measuredBearing.rotate(Point2(measuredRange, 0.0))));
373  }
374  }
375  else
376  {
377  throw std::runtime_error("Unknown factor type read from data file");
378  }
379  ++ nextMeasurement;
380  }
381  gttoc_(Collect_measurements);
382 
383  // Update iSAM2
384  try {
385  gttic_(Update_ISAM2);
386  isam2.update(newFactors, newVariables);
387  gttoc_(Update_ISAM2);
388  } catch(std::exception& e) {
389  cout << e.what() << endl;
390  exit(1);
391  }
392 
393  if((step - firstPose) % 1000 == 0) {
394  try {
395  gttic_(chi2);
396  Values estimate(isam2.calculateEstimate());
397  double chi2 = chi2_red(isam2.getFactorsUnsafe(), estimate);
398  cout << "chi2 = " << chi2 << endl;
399  gttoc_(chi2);
400  } catch(std::exception& e) {
401  cout << e.what() << endl;
402  exit(1);
403  }
404  }
405 
407 
408  if((step - firstPose) % 1000 == 0) {
409  cout << "Step " << step << endl;
410  tictoc_print_();
411  }
412  }
413 
414  if(!outputFile.empty())
415  {
416  try {
417  cout << "Writing output file " << outputFile << endl;
418  std::ofstream writerStream(outputFile.c_str(), ios::binary);
419  boost::archive::binary_oarchive writer(writerStream);
420  Values estimates = isam2.calculateEstimate();
421  writer << estimates;
422  } catch(std::exception& e) {
423  cout << e.what() << endl;
424  exit(1);
425  }
426  }
427 
428  tictoc_print_();
429 
430  // Compute marginals
431  //try {
432  // Marginals marginals(graph, values);
433  // int i=0;
434  // for (Key key1: boost::adaptors::reverse(values.keys())) {
435  // int j=0;
436  // for (Key key12: boost::adaptors::reverse(values.keys())) {
437  // if(i != j) {
438  // gttic_(jointMarginalInformation);
439  // KeyVector keys(2);
440  // keys[0] = key1;
441  // keys[1] = key2;
442  // JointMarginal info = marginals.jointMarginalInformation(keys);
443  // gttoc_(jointMarginalInformation);
444  // tictoc_finishedIteration_();
445  // }
446  // ++j;
447  // if(j >= 50)
448  // break;
449  // }
450  // ++i;
451  // if(i >= 50)
452  // break;
453  // }
454  // tictoc_print_();
455  // for(Key key: values.keys()) {
456  // gttic_(marginalInformation);
457  // Matrix info = marginals.marginalInformation(key);
458  // gttoc_(marginalInformation);
459  // tictoc_finishedIteration_();
460  // ++i;
461  // }
462  //} catch(std::exception& e) {
463  // cout << e.what() << endl;
464  //}
465  //tictoc_print_();
466 }
467 
468 /* ************************************************************************* */
469 void runBatch()
470 {
471  cout << "Creating batch optimizer..." << endl;
472 
474  measurements.addPrior(0, Pose(), noiseModel::Unit::Create(3));
475 
476  gttic_(Create_optimizer);
478  params.linearSolverType = NonlinearOptimizerParams::MULTIFRONTAL_CHOLESKY;
479  GaussNewtonOptimizer optimizer(measurements, initial, params);
480  gttoc_(Create_optimizer);
481  double lastError;
482  do {
483  lastError = optimizer.error();
484  gttic_(Iterate_optimizer);
485  optimizer.iterate();
486  gttoc_(Iterate_optimizer);
487  cout << "Error: " << lastError << " -> " << optimizer.error() /*<< ", lambda: " << optimizer.lambda()*/ << endl;
488  gttic_(chi2);
489  double chi2 = chi2_red(measurements, optimizer.values());
490  cout << "chi2 = " << chi2 << endl;
491  gttoc_(chi2);
492  } while(!checkConvergence(optimizer.params().relativeErrorTol,
493  optimizer.params().absoluteErrorTol, optimizer.params().errorTol,
494  lastError, optimizer.error(), optimizer.params().verbosity));
495 
497  tictoc_print_();
498 
499  if(!outputFile.empty())
500  {
501  try {
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;
508  exit(1);
509  }
510  }
511 }
512 
513 /* ************************************************************************* */
515 {
516  Values soln1, soln2;
517 
518  cout << "Reading solution file " << compareFile1 << endl;
519  {
520  std::ifstream readerStream(compareFile1.c_str(), ios::binary);
521  boost::archive::binary_iarchive reader(readerStream);
522  reader >> soln1;
523  }
524 
525  cout << "Reading solution file " << compareFile2 << endl;
526  {
527  std::ifstream readerStream(compareFile2.c_str(), ios::binary);
528  boost::archive::binary_iarchive reader(readerStream);
529  reader >> soln2;
530  }
531 
532  // Check solution for equality
533  cout << "Comparing solutions..." << endl;
534  KeyVector missingKeys;
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) {
539  cout << DefaultKeyFormatter(missingKeys[i]);
540  if(i != missingKeys.size() - 1)
541  cout << ", ";
542  }
543  cout << endl;
544  }
545  KeyVector commonKeys;
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;
551 }
552 
553 /* ************************************************************************* */
555 {
556  // Set up random number generator
557  std::mt19937 rng;
558  std::normal_distribution<double> normal(0.0, perturbationNoise);
559 
560  // Perturb values
561  VectorValues noise;
562  for(const Values::KeyValuePair key_val: initial)
563  {
564  Vector noisev(key_val.value.dim());
565  for(Vector::Index i = 0; i < noisev.size(); ++i)
566  noisev(i) = normal(rng);
567  noise.insert(key_val.key, noisev);
568  }
569  Values perturbed = initial.retract(noise);
570 
571  // Write results
572  try {
573  cout << "Writing output file " << outputFile << endl;
574  std::ofstream writerStream(outputFile.c_str(), ios::binary);
575  boost::archive::binary_oarchive writer(writerStream);
576  writer << perturbed;
577  } catch(std::exception& e) {
578  cout << e.what() << endl;
579  exit(1);
580  }
581 
582 }
583 
584 /* ************************************************************************* */
585 void runStats()
586 {
587  cout << "Gathering statistics..." << endl;
588  GaussianFactorGraph linear = *datasetMeasurements.linearize(initial);
589  GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::Colamd(linear)));
591 
592  ofstream file;
593 
594  cout << "Writing SolverComparer_Stats_problemSizeHistogram.txt..." << endl;
595  file.open("SolverComparer_Stats_problemSizeHistogram.txt");
596  treeTraversal::ForestStatistics::Write(file, statistics.problemSizeHistogram);
597  file.close();
598 
599  cout << "Writing SolverComparer_Stats_numberOfChildrenHistogram.txt..." << endl;
600  file.open("SolverComparer_Stats_numberOfChildrenHistogram.txt");
601  treeTraversal::ForestStatistics::Write(file, statistics.numberOfChildrenHistogram);
602  file.close();
603 
604  cout << "Writing SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt..." << endl;
605  file.open("SolverComparer_Stats_problemSizeOfSecondLargestChildHistogram.txt");
606  treeTraversal::ForestStatistics::Write(file, statistics.problemSizeOfSecondLargestChildHistogram);
607  file.close();
608 }
size_t dim() const
Definition: Values.cpp:207
const gtsam::Key poseKey
def step(data, isam, result, truth, currPoseIndex)
Definition: visual_isam.py:82
size_t size() const
Definition: FactorGraph.h:306
bool compare
void runCompare()
#define max(a, b)
Definition: datatypes.h:20
bool batch
bool exists(Key j) const
Definition: Values.cpp:104
#define gttic_(label)
Definition: timing.h:230
return int(ret)+1
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
Definition: Rot2.cpp:104
Pose2 Pose
boost::shared_ptr< This > shared_ptr
void insert(Key j, const Value &val)
Definition: Values.cpp:140
#define min(a, b)
Definition: datatypes.h:19
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
Definition: dataset.cpp:500
Vector2 Point2
Definition: Point2.h:27
static std::mt19937 rng
string compareFile2
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: Half.h:150
Struct to store gathered statistics about a forest.
Definition: statistics.h:31
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
void runIncremental()
NonlinearFactorGraph graph
KeyVector keys() const
Definition: Values.cpp:191
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
bool stats
int firstStep
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Definition: Pose2.cpp:228
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
const Symbol key1('v', 1)
double errorTol
The maximum total error to stop iterating (default 0.0)
string datasetName
Values calculateEstimate() const
Definition: ISAM2.cpp:763
string inputFile
boost::shared_ptr< BetweenFactor > shared_ptr
Definition: BetweenFactor.h:60
const GaussNewtonParams & params() const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
BearingRangeFactor< Pose, Point2 > BR
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
void runBatch()
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
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.
Definition: Meta.h:33
boost::shared_ptr< This > shared_ptr
string compareFile1
int relinSkip
int data[]
int lastStep
void tictoc_print_()
Definition: timing.h:253
Array< double, 1, 3 > e(1./3., 0.5, 2.)
bool perturb
bool dogleg
OptimizationParams optimizationParams
Definition: ISAM2Params.h:150
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
void runPerturb()
double perturbationNoise
void runStats()
string outputFile
NoiseModelFactor2< Pose, Pose > NM2
traits
Definition: chartTesting.h:28
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Definition: Pose2.cpp:218
GaussianFactorGraph::shared_ptr iterate() override
NonlinearFactorGraph datasetMeasurements
const Symbol key2('v', 2)
bool enablePartialRelinearizationCheck
Definition: ISAM2Params.h:218
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)
Definition: ISAM2.cpp:396
A class for computing marginals in a NonlinearFactorGraph.
void tictoc_finishedIteration_()
Definition: timing.h:249
const NonlinearFactorGraph & getFactorsUnsafe() const
Definition: ISAM2.h:257
2D Pose
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Point3 measured
#define gttoc_(label)
Definition: timing.h:235
void run(Expr &expr, Dev &dev)
Definition: TensorSyclRun.h:33
iterator insert(const std::pair< Key, Vector > &key_value)
ForestStatistics GatherStatistics(const FOREST &forest)
Definition: statistics.h:86
Values initial
utility functions for loading datasets
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
std::ptrdiff_t j
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Definition: Pose2.cpp:253
Timing utilities.
int main(int argc, char *argv[])
const Values & getLinearizationPoint() const
Access the current linearization point.
Definition: ISAM2.h:205
int nThreads
bool incremental
NoiseModelFactor1< Pose > NM1


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:17