ISAM2_City10000.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2020, 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  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/geometry/Pose2.h>
21 #include <gtsam/inference/Symbol.h>
22 #include <gtsam/nonlinear/ISAM2.h>
25 #include <gtsam/nonlinear/Values.h>
27 #include <gtsam/slam/dataset.h>
28 #include <time.h>
29 
30 #include <boost/algorithm/string/classification.hpp>
31 #include <boost/algorithm/string/split.hpp>
32 #include <fstream>
33 #include <string>
34 #include <vector>
35 
36 #include "City10000.h"
37 
38 using namespace gtsam;
39 
41 
42 // Experiment Class
43 class Experiment {
45  City10000Dataset dataset_;
46 
47  public:
48  // Parameters with default values
49  size_t maxLoopCount = 2000; // 200 //2000 //8000
50 
51  // false: run original iSAM2 without ambiguities
52  // true: run original iSAM2 with ambiguities
54 
55  private:
58  Values initial_;
60 
61  public:
63  explicit Experiment(const std::string& filename, bool isWithAmbiguity = false)
64  : dataset_(filename), isWithAmbiguity(isWithAmbiguity) {
66  parameters.optimizationParams = gtsam::ISAM2GaussNewtonParams(0.0);
67  parameters.relinearizeThreshold = 0.01;
68  parameters.relinearizeSkip = 1;
69  isam2_ = ISAM2(parameters);
70  }
71 
73  void run() {
74  // Initialize local variables
75  size_t index = 0;
76 
77  std::list<double> timeList;
78 
79  // Set up initial prior
80  Pose2 priorPose(0, 0, 0);
81  initial_.insert(X(0), priorPose);
82  graph_.addPrior<Pose2>(X(0), priorPose, kPriorNoiseModel);
83 
84  // Initial update
85  isam2_.update(graph_, initial_);
86  graph_.resize(0);
87  initial_.clear();
88  results = isam2_.calculateBestEstimate();
89 
90  // Start main loop
91  size_t keyS = 0;
92  size_t keyT = 0;
93  clock_t startTime = clock();
94 
95  std::vector<Pose2> poseArray;
96  std::pair<size_t, size_t> keys;
97 
98  while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) {
99  keyS = keys.first;
100  keyT = keys.second;
101  size_t numMeasurements = poseArray.size();
102 
103  Pose2 odomPose;
104  if (isWithAmbiguity) {
105  // Get wrong intentionally
106  int id = index % numMeasurements;
107  odomPose = Pose2(poseArray[id]);
108  } else {
109  odomPose = poseArray[0];
110  }
111 
112  if (keyS == keyT - 1) { // new X(key)
113  initial_.insert(X(keyT), results.at<Pose2>(X(keyS)) * odomPose);
114  graph_.add(
115  BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, kPoseNoiseModel));
116 
117  } else { // loop
118  int id = index % numMeasurements;
119  if (isWithAmbiguity && id % 2 == 0) {
120  graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
121  kPoseNoiseModel));
122  } else {
123  graph_.add(BetweenFactor<Pose2>(
124  X(keyS), X(keyT), odomPose,
125  noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10.0)));
126  }
127  index++;
128  }
129 
130  isam2_.update(graph_, initial_);
131  graph_.resize(0);
132  initial_.clear();
133  results = isam2_.calculateBestEstimate();
134 
135  // Print loop index and time taken in processor clock ticks
136  if (index % 50 == 0 && keyS != keyT - 1) {
137  std::cout << "index: " << index << std::endl;
138  std::cout << "accTime: " << timeList.back() / CLOCKS_PER_SEC
139  << std::endl;
140  }
141 
142  if (keyS == keyT - 1) {
143  clock_t curTime = clock();
144  timeList.push_back(curTime - startTime);
145  }
146 
147  if (timeList.size() % 100 == 0 && (keyS == keyT - 1)) {
148  std::string stepFileIdx = std::to_string(100000 + timeList.size());
149 
150  std::ofstream stepOutfile;
151  std::string stepFileName = "step_files/ISAM2_City10000_S" + stepFileIdx;
152  stepOutfile.open(stepFileName + ".txt");
153  for (size_t i = 0; i < (keyT + 1); ++i) {
154  Pose2 outPose = results.at<Pose2>(X(i));
155  stepOutfile << outPose.x() << " " << outPose.y() << " "
156  << outPose.theta() << std::endl;
157  }
158  stepOutfile.close();
159  }
160  }
161 
162  clock_t endTime = clock();
163  clock_t totalTime = endTime - startTime;
164  std::cout << "totalTime: " << totalTime / CLOCKS_PER_SEC << std::endl;
165 
167  writeResult(results, (keyT + 1), "ISAM2_City10000.txt");
168 
169  std::ofstream outfileTime;
170  std::string timeFileName = "ISAM2_City10000_time.txt";
171  outfileTime.open(timeFileName);
172  for (auto accTime : timeList) {
173  outfileTime << accTime << std::endl;
174  }
175  outfileTime.close();
176  std::cout << "Written cumulative time to: " << timeFileName << " file."
177  << std::endl;
178  }
179 };
180 
181 /* ************************************************************************* */
182 // Function to parse command-line arguments
183 void parseArguments(int argc, char* argv[], size_t& maxLoopCount,
184  bool& isWithAmbiguity) {
185  for (int i = 1; i < argc; ++i) {
186  std::string arg = argv[i];
187  if (arg == "--max-loop-count" && i + 1 < argc) {
188  maxLoopCount = std::stoul(argv[++i]);
189  } else if (arg == "--is-with-ambiguity" && i + 1 < argc) {
190  isWithAmbiguity = bool(std::stoul(argv[++i]));
191  } else if (arg == "--help") {
192  std::cout << "Usage: " << argv[0] << " [options]\n"
193  << "Options:\n"
194  << " --max-loop-count <value> Set the maximum loop "
195  "count (default: 2000)\n"
196  << " --is-with-ambiguity <value=0/1> Set whether to use "
197  "ambiguous measurements "
198  "(default: false)\n"
199  << " --help Show this help message\n";
200  std::exit(0);
201  }
202  }
203 }
204 
205 /* ************************************************************************* */
206 int main(int argc, char* argv[]) {
207  Experiment experiment(findExampleDataFile("T1_City10000_04.txt"));
208  // Experiment experiment("../data/mh_T1_City10000_04.txt"); //Type #1 only
209  // Experiment experiment("../data/mh_T3b_City10000_10.txt"); //Type #3 only
210  // Experiment experiment("../data/mh_T1_T3_City10000_04.txt"); //Type #1 +
211  // Type #3
212 
213  // Parse command-line arguments
214  parseArguments(argc, argv, experiment.maxLoopCount,
215  experiment.isWithAmbiguity);
216 
217  // Run the experiment
218  experiment.run();
219 
220  return 0;
221 }
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
Pose2.h
2D Pose
gtsam::ISAM2
Definition: ISAM2.h:45
gtsam::ISAM2::calculateBestEstimate
Values calculateBestEstimate() const
Definition: ISAM2.cpp:801
ISAM2Params.h
Parameters for iSAM 2.
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
City10000Dataset::next
bool next(std::vector< Pose2 > *poseArray, std::pair< size_t, size_t > *keys)
Read and parse the next line.
Definition: City10000.h:81
Experiment::graph_
NonlinearFactorGraph graph_
Definition: ISAM2_City10000.cpp:57
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:283
X
#define X
Definition: icosphere.cpp:20
main
int main(int argc, char *argv[])
Definition: ISAM2_City10000.cpp:206
Experiment::maxLoopCount
size_t maxLoopCount
Definition: Hybrid_City10000.cpp:53
kPriorNoiseModel
auto kPriorNoiseModel
Definition: City10000.h:30
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
dataset.h
utility functions for loading datasets
BetweenFactor.h
relicense.filename
filename
Definition: relicense.py:57
Experiment
Definition: Hybrid_City10000.cpp:47
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
Experiment::Experiment
Experiment(const std::string &filename, bool isWithAmbiguity=false)
Construct with filename of experiment to run.
Definition: ISAM2_City10000.cpp:63
arg
Definition: cast.h:1419
Experiment::results
Values results
Definition: ISAM2_City10000.cpp:59
kPoseNoiseModel
auto kPoseNoiseModel
Definition: City10000.h:33
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::ISAM2GaussNewtonParams
Definition: ISAM2Params.h:36
Symbol.h
writeResult
void writeResult(const Values &result, size_t numPoses, const std::string &filename="Hybrid_city10000.txt")
Write the result of optimization to file.
Definition: City10000.h:98
gtsam::Pose2::theta
double theta() const
get theta
Definition: Pose2.h:253
parseArguments
void parseArguments(int argc, char *argv[], size_t &maxLoopCount, bool &isWithAmbiguity)
Definition: ISAM2_City10000.cpp:183
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
City10000.h
Class for City10000 dataset.
gtsam
traits
Definition: SFMdata.h:40
gtsam::ISAM2::update
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Definition: ISAM2.cpp:401
City10000Dataset
Definition: City10000.h:37
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
gtsam::Pose2::x
double x() const
get x
Definition: Pose2.h:247
gtsam::Values::clear
void clear()
Definition: Values.h:347
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
Experiment::isWithAmbiguity
bool isWithAmbiguity
Definition: ISAM2_City10000.cpp:53
Experiment::run
void run()
Run the main experiment with a given maxLoopCount.
Definition: ISAM2_City10000.cpp:73
results
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
Definition: dense_solvers.cpp:10
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
Experiment::isam2_
ISAM2 isam2_
Definition: ISAM2_City10000.cpp:56
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::Pose2::y
double y() const
get y
Definition: Pose2.h:250
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::Pose2
Definition: Pose2.h:39
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:54