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::vector<std::pair<size_t, double>> smootherUpdateTimes;
78 
79  std::list<double> timeList;
80 
81  // Set up initial prior
82  Pose2 priorPose(0, 0, 0);
83  initial_.insert(X(0), priorPose);
84  graph_.addPrior<Pose2>(X(0), priorPose, kPriorNoiseModel);
85 
86  // Initial update
87  clock_t beforeUpdate = clock();
88  isam2_.update(graph_, initial_);
89  results = isam2_.calculateBestEstimate();
90  clock_t afterUpdate = clock();
91  smootherUpdateTimes.push_back(
92  std::make_pair(index, afterUpdate - beforeUpdate));
93  graph_.resize(0);
94  initial_.clear();
95  index += 1;
96 
97  // Start main loop
98  size_t keyS = 0;
99  size_t keyT = 0;
100  clock_t startTime = clock();
101 
102  std::vector<Pose2> poseArray;
103  std::pair<size_t, size_t> keys;
104 
105  while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) {
106  keyS = keys.first;
107  keyT = keys.second;
108  size_t numMeasurements = poseArray.size();
109 
110  Pose2 odomPose;
111  if (isWithAmbiguity) {
112  // Get wrong intentionally
113  int id = index % numMeasurements;
114  odomPose = Pose2(poseArray[id]);
115  } else {
116  odomPose = poseArray[0];
117  }
118 
119  if (keyS == keyT - 1) { // new X(key)
120  initial_.insert(X(keyT), results.at<Pose2>(X(keyS)) * odomPose);
121  graph_.add(
122  BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, kPoseNoiseModel));
123 
124  } else { // loop
125  int id = index % numMeasurements;
126  if (isWithAmbiguity && id % 2 == 0) {
127  graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
128  kPoseNoiseModel));
129  } else {
130  graph_.add(BetweenFactor<Pose2>(
131  X(keyS), X(keyT), odomPose,
132  noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10.0)));
133  }
134  index++;
135  }
136 
137  clock_t beforeUpdate = clock();
138  isam2_.update(graph_, initial_);
139  results = isam2_.calculateBestEstimate();
140  clock_t afterUpdate = clock();
141  smootherUpdateTimes.push_back(
142  std::make_pair(index, afterUpdate - beforeUpdate));
143  graph_.resize(0);
144  initial_.clear();
145  index += 1;
146 
147  // Print loop index and time taken in processor clock ticks
148  if (index % 50 == 0 && keyS != keyT - 1) {
149  std::cout << "index: " << index << std::endl;
150  std::cout << "accTime: " << timeList.back() / CLOCKS_PER_SEC
151  << std::endl;
152  }
153 
154  if (keyS == keyT - 1) {
155  clock_t curTime = clock();
156  timeList.push_back(curTime - startTime);
157  }
158 
159  if (timeList.size() % 100 == 0 && (keyS == keyT - 1)) {
160  std::string stepFileIdx = std::to_string(100000 + timeList.size());
161 
162  std::ofstream stepOutfile;
163  std::string stepFileName = "step_files/ISAM2_City10000_S" + stepFileIdx;
164  stepOutfile.open(stepFileName + ".txt");
165  for (size_t i = 0; i < (keyT + 1); ++i) {
166  Pose2 outPose = results.at<Pose2>(X(i));
167  stepOutfile << outPose.x() << " " << outPose.y() << " "
168  << outPose.theta() << std::endl;
169  }
170  stepOutfile.close();
171  }
172  }
173 
174  clock_t endTime = clock();
175  clock_t totalTime = endTime - startTime;
176  std::cout << "totalTime: " << totalTime / CLOCKS_PER_SEC << std::endl;
177 
179  writeResult(results, (keyT + 1), "ISAM2_City10000.txt");
180 
181  std::ofstream outfileTime;
182  std::string timeFileName = "ISAM2_City10000_time.txt";
183  outfileTime.open(timeFileName);
184  for (auto accTime : timeList) {
185  outfileTime << accTime << std::endl;
186  }
187  outfileTime.close();
188  std::cout << "Written cumulative time to: " << timeFileName << " file."
189  << std::endl;
190 
191  std::ofstream timingFile;
192  std::string timingFileName = "ISAM2_City10000_timing.txt";
193  timingFile.open(timingFileName);
194  for (size_t i = 0; i < smootherUpdateTimes.size(); i++) {
195  auto p = smootherUpdateTimes.at(i);
196  timingFile << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl;
197  }
198  timingFile.close();
199  std::cout << "Wrote timing information to " << timingFileName << std::endl;
200  }
201 };
202 
203 /* ************************************************************************* */
204 // Function to parse command-line arguments
205 void parseArguments(int argc, char* argv[], size_t& maxLoopCount,
206  bool& isWithAmbiguity) {
207  for (int i = 1; i < argc; ++i) {
208  std::string arg = argv[i];
209  if (arg == "--max-loop-count" && i + 1 < argc) {
210  maxLoopCount = std::stoul(argv[++i]);
211  } else if (arg == "--is-with-ambiguity" && i + 1 < argc) {
212  isWithAmbiguity = bool(std::stoul(argv[++i]));
213  } else if (arg == "--help") {
214  std::cout << "Usage: " << argv[0] << " [options]\n"
215  << "Options:\n"
216  << " --max-loop-count <value> Set the maximum loop "
217  "count (default: 2000)\n"
218  << " --is-with-ambiguity <value=0/1> Set whether to use "
219  "ambiguous measurements "
220  "(default: false)\n"
221  << " --help Show this help message\n";
222  std::exit(0);
223  }
224  }
225 }
226 
227 /* ************************************************************************* */
228 int main(int argc, char* argv[]) {
229  Experiment experiment(findExampleDataFile("T1_City10000_04.txt"));
230  // Experiment experiment("../data/mh_T1_City10000_04.txt"); //Type #1 only
231  // Experiment experiment("../data/mh_T3b_City10000_10.txt"); //Type #3 only
232  // Experiment experiment("../data/mh_T1_T3_City10000_04.txt"); //Type #1 +
233  // Type #3
234 
235  // Parse command-line arguments
236  parseArguments(argc, argv, experiment.maxLoopCount,
237  experiment.isWithAmbiguity);
238 
239  // Run the experiment
240  experiment.run();
241 
242  return 0;
243 }
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:228
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:205
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
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: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 Thu Apr 10 2025 03:01:40