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 <fstream>
31 #include <string>
32 #include <vector>
33 
34 #include "City10000.h"
35 
36 using namespace gtsam;
37 
39 
40 // Experiment Class
41 class Experiment {
43  City10000Dataset dataset_;
44 
45  public:
46  // Parameters with default values
47  size_t maxLoopCount = 2000; // 200 //2000 //8000
48 
49  // false: run original iSAM2 without ambiguities
50  // true: run original iSAM2 with ambiguities
52 
53  private:
56  Values initial_;
58 
59  public:
61  explicit Experiment(const std::string& filename, bool isWithAmbiguity = false)
62  : dataset_(filename), isWithAmbiguity(isWithAmbiguity) {
64  parameters.optimizationParams = gtsam::ISAM2GaussNewtonParams(0.0);
65  parameters.relinearizeThreshold = 0.01;
66  parameters.relinearizeSkip = 1;
67  isam2_ = ISAM2(parameters);
68  }
69 
71  void run() {
72  // Initialize local variables
73  size_t index = 0;
74 
75  std::vector<std::pair<size_t, double>> smootherUpdateTimes;
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  clock_t beforeUpdate = clock();
86  isam2_.update(graph_, initial_);
87  results = isam2_.calculateBestEstimate();
88  clock_t afterUpdate = clock();
89  smootherUpdateTimes.push_back(
90  std::make_pair(index, afterUpdate - beforeUpdate));
91  graph_.resize(0);
92  initial_.clear();
93  index += 1;
94 
95  // Start main loop
96  size_t keyS = 0;
97  size_t keyT = 0;
98  clock_t startTime = clock();
99 
100  std::vector<Pose2> poseArray;
101  std::pair<size_t, size_t> keys;
102 
103  while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) {
104  keyS = keys.first;
105  keyT = keys.second;
106  size_t numMeasurements = poseArray.size();
107 
108  Pose2 odomPose;
109  if (isWithAmbiguity) {
110  // Get wrong intentionally
111  int id = index % numMeasurements;
112  odomPose = Pose2(poseArray[id]);
113  } else {
114  odomPose = poseArray[0];
115  }
116 
117  if (keyS == keyT - 1) { // new X(key)
118  initial_.insert(X(keyT), results.at<Pose2>(X(keyS)) * odomPose);
119  graph_.add(
120  BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, kPoseNoiseModel));
121 
122  } else { // loop
123  int id = index % numMeasurements;
124  if (isWithAmbiguity && id % 2 == 0) {
125  graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
126  kPoseNoiseModel));
127  } else {
128  graph_.add(BetweenFactor<Pose2>(
129  X(keyS), X(keyT), odomPose,
130  noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10.0)));
131  }
132  index++;
133  }
134 
135  clock_t beforeUpdate = clock();
136  isam2_.update(graph_, initial_);
137  results = isam2_.calculateBestEstimate();
138  clock_t afterUpdate = clock();
139  smootherUpdateTimes.push_back(
140  std::make_pair(index, afterUpdate - beforeUpdate));
141  graph_.resize(0);
142  initial_.clear();
143  index += 1;
144 
145  // Print loop index and time taken in processor clock ticks
146  if (index % 50 == 0 && keyS != keyT - 1) {
147  std::cout << "index: " << index << std::endl;
148  std::cout << "accTime: " << timeList.back() / CLOCKS_PER_SEC
149  << std::endl;
150  }
151 
152  if (keyS == keyT - 1) {
153  clock_t curTime = clock();
154  timeList.push_back(curTime - startTime);
155  }
156 
157  if (timeList.size() % 100 == 0 && (keyS == keyT - 1)) {
158  std::string stepFileIdx = std::to_string(100000 + timeList.size());
159 
160  std::ofstream stepOutfile;
161  std::string stepFileName = "step_files/ISAM2_City10000_S" + stepFileIdx;
162  stepOutfile.open(stepFileName + ".txt");
163  for (size_t i = 0; i < (keyT + 1); ++i) {
164  Pose2 outPose = results.at<Pose2>(X(i));
165  stepOutfile << outPose.x() << " " << outPose.y() << " "
166  << outPose.theta() << std::endl;
167  }
168  stepOutfile.close();
169  }
170  }
171 
172  clock_t endTime = clock();
173  clock_t totalTime = endTime - startTime;
174  std::cout << "totalTime: " << totalTime / CLOCKS_PER_SEC << std::endl;
175 
177  writeResult(results, (keyT + 1), "ISAM2_City10000.txt");
178 
179  std::ofstream outfileTime;
180  std::string timeFileName = "ISAM2_City10000_time.txt";
181  outfileTime.open(timeFileName);
182  for (auto accTime : timeList) {
183  outfileTime << accTime << std::endl;
184  }
185  outfileTime.close();
186  std::cout << "Written cumulative time to: " << timeFileName << " file."
187  << std::endl;
188 
189  std::ofstream timingFile;
190  std::string timingFileName = "ISAM2_City10000_timing.txt";
191  timingFile.open(timingFileName);
192  for (size_t i = 0; i < smootherUpdateTimes.size(); i++) {
193  auto p = smootherUpdateTimes.at(i);
194  timingFile << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl;
195  }
196  timingFile.close();
197  std::cout << "Wrote timing information to " << timingFileName << std::endl;
198  }
199 };
200 
201 /* ************************************************************************* */
202 // Function to parse command-line arguments
203 void parseArguments(int argc, char* argv[], size_t& maxLoopCount,
204  bool& isWithAmbiguity) {
205  for (int i = 1; i < argc; ++i) {
206  std::string arg = argv[i];
207  if (arg == "--max-loop-count" && i + 1 < argc) {
208  maxLoopCount = std::stoul(argv[++i]);
209  } else if (arg == "--is-with-ambiguity" && i + 1 < argc) {
210  isWithAmbiguity = bool(std::stoul(argv[++i]));
211  } else if (arg == "--help") {
212  std::cout << "Usage: " << argv[0] << " [options]\n"
213  << "Options:\n"
214  << " --max-loop-count <value> Set the maximum loop "
215  "count (default: 2000)\n"
216  << " --is-with-ambiguity <value=0/1> Set whether to use "
217  "ambiguous measurements "
218  "(default: false)\n"
219  << " --help Show this help message\n";
220  std::exit(0);
221  }
222  }
223 }
224 
225 /* ************************************************************************* */
226 int main(int argc, char* argv[]) {
227  Experiment experiment(findExampleDataFile("T1_City10000_04.txt"));
228  // Experiment experiment("../data/mh_T1_City10000_04.txt"); //Type #1 only
229  // Experiment experiment("../data/mh_T3b_City10000_10.txt"); //Type #3 only
230  // Experiment experiment("../data/mh_T1_T3_City10000_04.txt"); //Type #1 +
231  // Type #3
232 
233  // Parse command-line arguments
234  parseArguments(argc, argv, experiment.maxLoopCount,
235  experiment.isWithAmbiguity);
236 
237  // Run the experiment
238  experiment.run();
239 
240  return 0;
241 }
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:55
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:226
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:61
arg
Definition: cast.h:1419
Experiment::results
Values results
Definition: ISAM2_City10000.cpp:57
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:203
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
City10000.h
Class for City10000 dataset.
gtsam
traits
Definition: ABC.h:17
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
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
Experiment::isWithAmbiguity
bool isWithAmbiguity
Definition: ISAM2_City10000.cpp:51
Experiment::run
void run()
Run the main experiment with a given maxLoopCount.
Definition: ISAM2_City10000.cpp:71
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:54
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 May 28 2025 03:01:32