Hybrid_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>
25 #include <gtsam/inference/Symbol.h>
26 #include <gtsam/nonlinear/Values.h>
28 #include <gtsam/slam/PriorFactor.h>
29 #include <gtsam/slam/dataset.h>
30 #include <time.h>
31 
32 #include <cstdlib>
33 #include <fstream>
34 #include <iostream>
35 #include <string>
36 #include <vector>
37 
38 #include "City10000.h"
39 
40 using namespace gtsam;
41 
45 
46 // Experiment Class
47 class Experiment {
50 
51  public:
52  // Parameters with default values
53  size_t maxLoopCount = 8000;
54 
55  // 3000: {1: 62s, 2: 21s, 3: 20s, 4: 31s, 5: 39s} No DT optimizations
56  // 3000: {1: 65s, 2: 20s, 3: 16s, 4: 21s, 5: 28s} With DT optimizations
57  // 3000: {1: 59s, 2: 19s, 3: 18s, 4: 26s, 5: 33s} With DT optimizations +
58  // merge
59  size_t updateFrequency = 3;
60 
61  size_t maxNrHypotheses = 10;
62 
63  size_t reLinearizationFrequency = 10;
64 
65  double marginalThreshold = 0.9999;
66 
67  private:
71 
77  size_t loopCounter, size_t keyS, size_t keyT,
78  const Pose2& measurement) const {
79  DiscreteKey l(L(loopCounter), 2);
80 
81  auto f0 = std::make_shared<BetweenFactor<Pose2>>(
82  X(keyS), X(keyT), measurement, kOpenLoopModel);
83  auto f1 = std::make_shared<BetweenFactor<Pose2>>(
84  X(keyS), X(keyT), measurement, kPoseNoiseModel);
85 
86  std::vector<NonlinearFactorValuePair> factors{{f0, kOpenLoopConstant},
88  HybridNonlinearFactor mixtureFactor(l, factors);
89  return mixtureFactor;
90  }
91 
94  size_t numMeasurements, size_t keyS, size_t keyT, const DiscreteKey& m,
95  const std::vector<Pose2>& poseArray) const {
96  auto f0 = std::make_shared<BetweenFactor<Pose2>>(
97  X(keyS), X(keyT), poseArray[0], kPoseNoiseModel);
98  auto f1 = std::make_shared<BetweenFactor<Pose2>>(
99  X(keyS), X(keyT), poseArray[1], kPoseNoiseModel);
100 
101  std::vector<NonlinearFactorValuePair> factors{{f0, kPoseNoiseConstant},
103  HybridNonlinearFactor mixtureFactor(m, factors);
104  return mixtureFactor;
105  }
106 
108  clock_t smootherUpdate(size_t maxNrHypotheses) {
109  std::cout << "Smoother update: " << newFactors_.size() << std::endl;
110  gttic_(SmootherUpdate);
111  clock_t beforeUpdate = clock();
112  auto linearized = newFactors_.linearize(initial_);
113  smoother_.update(*linearized, maxNrHypotheses);
114  allFactors_.push_back(newFactors_);
115  newFactors_.resize(0);
116  clock_t afterUpdate = clock();
117  return afterUpdate - beforeUpdate;
118  }
119 
121  clock_t reInitialize() {
122  std::cout << "================= Re-Initialize: " << allFactors_.size()
123  << std::endl;
124  clock_t beforeUpdate = clock();
125  allFactors_ = allFactors_.restrict(smoother_.fixedValues());
126  auto linearized = allFactors_.linearize(initial_);
127  auto bayesNet = linearized->eliminateSequential();
128  HybridValues delta = bayesNet->optimize();
129  initial_ = initial_.retract(delta.continuous());
130  smoother_.reInitialize(std::move(*bayesNet));
131  clock_t afterUpdate = clock();
132  std::cout << "Took " << (afterUpdate - beforeUpdate) / CLOCKS_PER_SEC
133  << " seconds." << std::endl;
134  return afterUpdate - beforeUpdate;
135  }
136 
137  public:
139  explicit Experiment(const std::string& filename)
140  : dataset_(filename), smoother_(marginalThreshold) {}
141 
143  void run() {
144  // Initialize local variables
145  size_t discreteCount = 0, index = 0, loopCount = 0, updateCount = 0;
146 
147  std::list<double> timeList;
148 
149  // Set up initial prior
150  Pose2 priorPose(0, 0, 0);
151  initial_.insert(X(0), priorPose);
152  newFactors_.push_back(
153  PriorFactor<Pose2>(X(0), priorPose, kPriorNoiseModel));
154 
155  // Initial update
156  auto time = smootherUpdate(maxNrHypotheses);
157  std::vector<std::pair<size_t, double>> smootherUpdateTimes;
158  smootherUpdateTimes.push_back({index, time});
159 
160  // Flag to decide whether to run smoother update
161  size_t numberOfHybridFactors = 0;
162 
163  // Start main loop
164  Values result;
165  size_t keyS = 0, keyT = 0;
166  clock_t startTime = clock();
167 
168  std::vector<Pose2> poseArray;
169  std::pair<size_t, size_t> keys;
170 
171  while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) {
172  keyS = keys.first;
173  keyT = keys.second;
174  size_t numMeasurements = poseArray.size();
175 
176  // Take the first one as the initial estimate
177  Pose2 odomPose = poseArray[0];
178  if (keyS == keyT - 1) {
179  // Odometry factor
180  if (numMeasurements > 1) {
181  // Add hybrid factor
182  DiscreteKey m(M(discreteCount), numMeasurements);
183  HybridNonlinearFactor mixtureFactor =
184  hybridOdometryFactor(numMeasurements, keyS, keyT, m, poseArray);
185  newFactors_.push_back(mixtureFactor);
186  discreteCount++;
187  numberOfHybridFactors += 1;
188  std::cout << "mixtureFactor: " << keyS << " " << keyT << std::endl;
189  } else {
190  newFactors_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
191  kPoseNoiseModel));
192  }
193  // Insert next pose initial guess
194  initial_.insert(X(keyT), initial_.at<Pose2>(X(keyS)) * odomPose);
195  } else {
196  // Loop closure
197  HybridNonlinearFactor loopFactor =
198  hybridLoopClosureFactor(loopCount, keyS, keyT, odomPose);
199  // print loop closure event keys:
200  std::cout << "Loop closure: " << keyS << " " << keyT << std::endl;
201  newFactors_.add(loopFactor);
202  numberOfHybridFactors += 1;
203  loopCount++;
204  }
205 
206  if (numberOfHybridFactors >= updateFrequency) {
207  auto time = smootherUpdate(maxNrHypotheses);
208  smootherUpdateTimes.push_back({index, time});
209  numberOfHybridFactors = 0;
210  updateCount++;
211 
212  if (updateCount % reLinearizationFrequency == 0) {
213  reInitialize();
214  }
215  }
216 
217  // Record timing for odometry edges only
218  if (keyS == keyT - 1) {
219  clock_t curTime = clock();
220  timeList.push_back(curTime - startTime);
221  }
222 
223  // Print some status every 100 steps
224  if (index % 100 == 0) {
225  std::cout << "Index: " << index << std::endl;
226  if (!timeList.empty()) {
227  std::cout << "Acc_time: " << timeList.back() / CLOCKS_PER_SEC
228  << " seconds" << std::endl;
229  // delta.discrete().print("The Discrete Assignment");
231  tictoc_print_();
232  }
233  }
234 
235  index++;
236  }
237 
238  // Final update
239  time = smootherUpdate(maxNrHypotheses);
240  smootherUpdateTimes.push_back({index, time});
241 
242  // Final optimize
243  gttic_(HybridSmootherOptimize);
244  HybridValues delta = smoother_.optimize();
245  gttoc_(HybridSmootherOptimize);
246 
247  result.insert_or_assign(initial_.retract(delta.continuous()));
248 
249  std::cout << "Final error: " << smoother_.hybridBayesNet().error(delta)
250  << std::endl;
251 
252  clock_t endTime = clock();
253  clock_t totalTime = endTime - startTime;
254  std::cout << "Total time: " << totalTime / CLOCKS_PER_SEC << " seconds"
255  << std::endl;
256 
257  // Write results to file
258  writeResult(result, keyT + 1, "Hybrid_City10000.txt");
259 
260  // Write timing info to file
261  std::ofstream outfileTime;
262  std::string timeFileName = "Hybrid_City10000_time.txt";
263  outfileTime.open(timeFileName);
264  for (auto accTime : timeList) {
265  outfileTime << accTime << std::endl;
266  }
267  outfileTime.close();
268  std::cout << "Output " << timeFileName << " file." << std::endl;
269  }
270 };
271 
272 /* ************************************************************************* */
273 // Function to parse command-line arguments
274 void parseArguments(int argc, char* argv[], size_t& maxLoopCount,
275  size_t& updateFrequency, size_t& maxNrHypotheses) {
276  for (int i = 1; i < argc; ++i) {
277  std::string arg = argv[i];
278  if (arg == "--max-loop-count" && i + 1 < argc) {
279  maxLoopCount = std::stoul(argv[++i]);
280  } else if (arg == "--update-frequency" && i + 1 < argc) {
281  updateFrequency = std::stoul(argv[++i]);
282  } else if (arg == "--max-nr-hypotheses" && i + 1 < argc) {
283  maxNrHypotheses = std::stoul(argv[++i]);
284  } else if (arg == "--help") {
285  std::cout << "Usage: " << argv[0] << " [options]\n"
286  << "Options:\n"
287  << " --max-loop-count <value> Set the maximum loop "
288  "count (default: 3000)\n"
289  << " --update-frequency <value> Set the update frequency "
290  "(default: 3)\n"
291  << " --max-nr-hypotheses <value> Set the maximum number of "
292  "hypotheses (default: 10)\n"
293  << " --help Show this help message\n";
294  std::exit(0);
295  }
296  }
297 }
298 
299 /* ************************************************************************* */
300 // Main function
301 int main(int argc, char* argv[]) {
302  Experiment experiment(findExampleDataFile("T1_city10000_04.txt"));
303  // Experiment experiment("../data/mh_T1_city10000_04.txt"); //Type #1 only
304  // Experiment experiment("../data/mh_T3b_city10000_10.txt"); //Type #3 only
305  // Experiment experiment("../data/mh_T1_T3_city10000_04.txt"); //Type #1 +
306  // Type #3
307 
308  // Parse command-line arguments
309  parseArguments(argc, argv, experiment.maxLoopCount,
310  experiment.updateFrequency, experiment.maxNrHypotheses);
311 
312  // Run the experiment
313  experiment.run();
314 
315  return 0;
316 }
gtsam::HybridSmoother::hybridBayesNet
const HybridBayesNet & hybridBayesNet() const
Return the Bayes Net posterior.
Definition: HybridSmoother.cpp:273
Pose2.h
2D Pose
gtsam::HybridValues
Definition: HybridValues.h:37
asia::bayesNet
static const DiscreteBayesNet bayesNet
Definition: testDiscreteSearch.cpp:30
Experiment::newFactors_
HybridNonlinearFactorGraph newFactors_
Definition: Hybrid_City10000.cpp:69
test_constructor::f1
auto f1
Definition: testHybridNonlinearFactor.cpp:56
gtsam::HybridSmoother::update
void update(const HybridNonlinearFactorGraph &graph, const Values &initial, std::optional< size_t > maxNrLeaves={}, const std::optional< Ordering > givenOrdering={})
Definition: HybridSmoother.cpp:99
Experiment::smoother_
HybridSmoother smoother_
Definition: Hybrid_City10000.cpp:68
gtsam::FactorGraph::error
double error(const HybridValues &values) const
Definition: FactorGraph-inst.h:66
HybridNonlinearFactorGraph.h
Nonlinear hybrid factor graph that uses type erasure.
main
int main(int argc, char *argv[])
Definition: Hybrid_City10000.cpp:301
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::symbol_shorthand::M
Key M(std::uint64_t j)
Definition: inference/Symbol.h:160
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
Experiment::hybridOdometryFactor
HybridNonlinearFactor hybridOdometryFactor(size_t numMeasurements, size_t keyS, size_t keyT, const DiscreteKey &m, const std::vector< Pose2 > &poseArray) const
Create hybrid odometry factor with discrete measurement choices.
Definition: Hybrid_City10000.cpp:93
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
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
X
#define X
Definition: icosphere.cpp:20
Experiment::maxLoopCount
size_t maxLoopCount
Definition: Hybrid_City10000.cpp:53
kPriorNoiseModel
auto kPriorNoiseModel
Definition: City10000.h:30
kPoseNoiseConstant
const double kPoseNoiseConstant
Definition: City10000.h:35
result
Values result
Definition: OdometryOptimize.cpp:8
Experiment::initial_
Values initial_
Definition: Hybrid_City10000.cpp:70
HybridSmoother.h
An incremental smoother for hybrid factor graphs.
Experiment::maxNrHypotheses
size_t maxNrHypotheses
Definition: Hybrid_City10000.cpp:61
parseArguments
void parseArguments(int argc, char *argv[], size_t &maxLoopCount, size_t &updateFrequency, size_t &maxNrHypotheses)
Definition: Hybrid_City10000.cpp:274
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
Experiment::reInitialize
clock_t reInitialize()
Re-linearize, solve ALL, and re-initialize smoother.
Definition: Hybrid_City10000.cpp:121
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:99
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
dataset.h
utility functions for loading datasets
test_constructor::f0
auto f0
Definition: testHybridNonlinearFactor.cpp:55
gttoc_
#define gttoc_(label)
Definition: timing.h:273
BetweenFactor.h
gttic_
#define gttic_(label)
Definition: timing.h:268
gtsam::tictoc_finishedIteration_
void tictoc_finishedIteration_()
Definition: timing.h:287
relicense.filename
filename
Definition: relicense.py:57
Experiment
Definition: Hybrid_City10000.cpp:47
l
static const Line3 l(Rot3(), 1, 1)
arg
Definition: cast.h:1419
kPoseNoiseModel
auto kPoseNoiseModel
Definition: City10000.h:33
gtsam::tictoc_print_
void tictoc_print_()
Definition: timing.h:291
gtsam::HybridSmoother::optimize
HybridValues optimize() const
Optimize the hybrid Bayes Net, taking into accound fixed values.
Definition: HybridSmoother.cpp:278
Experiment::updateFrequency
size_t updateFrequency
Definition: Hybrid_City10000.cpp:59
L
MatrixXd L
Definition: LLT_example.cpp:6
Symbol.h
gtsam::symbol_shorthand::L
Key L(std::uint64_t j)
Definition: inference/Symbol.h:159
Experiment::dataset_
City10000Dataset dataset_
The City10000 dataset.
Definition: Hybrid_City10000.cpp:49
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
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
time
#define time
Definition: timeAdaptAutoDiff.cpp:31
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::HybridSmoother::reInitialize
void reInitialize(HybridBayesNet &&hybridBayesNet)
Definition: HybridSmoother.cpp:28
gtsam::HybridSmoother
Definition: HybridSmoother.h:28
City10000.h
Class for City10000 dataset.
HybridNonlinearFactor.h
A set of nonlinear factors indexed by a set of discrete keys.
gtsam::HybridNonlinearFactorGraph::restrict
HybridNonlinearFactorGraph restrict(const DiscreteValues &assignment) const
Restrict all factors in the graph to the given discrete values.
Definition: HybridNonlinearFactorGraph.cpp:225
Experiment::Experiment
Experiment(const std::string &filename)
Construct with filename of experiment to run.
Definition: Hybrid_City10000.cpp:139
gtsam
traits
Definition: SFMdata.h:40
Experiment::hybridLoopClosureFactor
HybridNonlinearFactor hybridLoopClosureFactor(size_t loopCounter, size_t keyS, size_t keyT, const Pose2 &measurement) const
Create a hybrid loop closure factor where 0 - loose noise model and 1 - loop noise model.
Definition: Hybrid_City10000.cpp:76
PriorFactor.h
City10000Dataset
Definition: City10000.h:37
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
gtsam::HybridNonlinearFactorGraph::linearize
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Definition: HybridNonlinearFactorGraph.cpp:139
Experiment::smootherUpdate
clock_t smootherUpdate(size_t maxNrHypotheses)
Perform smoother update and optimize the graph.
Definition: Hybrid_City10000.cpp:108
kOpenLoopConstant
const double kOpenLoopConstant
Definition: City10000.h:28
Experiment::run
void run()
Run the main experiment with a given maxLoopCount.
Definition: Hybrid_City10000.cpp:143
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
gtsam::HybridSmoother::fixedValues
const DiscreteValues & fixedValues() const
Return fixed values:
Definition: HybridSmoother.h:50
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
HybridValues.h
kOpenLoopModel
auto kOpenLoopModel
Definition: City10000.h:27
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::HybridNonlinearFactor
Implementation of a discrete-conditioned hybrid factor.
Definition: HybridNonlinearFactor.h:58
measurement
static Point2 measurement(323.0, 240.0)
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::Pose2
Definition: Pose2.h:39
gtsam::Values::insert_or_assign
void insert_or_assign(Key j, const Value &val)
If key j exists, update value, else perform an insert.
Definition: Values.cpp:193
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


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