| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @file   Hybrid_City10000.cpp | 
					
						
							|  |  |  |  * @brief  Example of using hybrid estimation | 
					
						
							|  |  |  |  *         with multiple odometry measurements. | 
					
						
							|  |  |  |  * @author Varun Agrawal | 
					
						
							|  |  |  |  * @date   January 22, 2025 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | #include <gtsam/hybrid/HybridNonlinearFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/hybrid/HybridNonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2025-01-24 10:54:57 +08:00
										 |  |  | #include <gtsam/hybrid/HybridSmoother.h>
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | #include <gtsam/hybrid/HybridValues.h>
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <time.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  | #include <cstdlib>
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | #include <fstream>
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  | #include "City10000.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  | using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | using symbol_shorthand::M; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | using symbol_shorthand::X; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | // Experiment Class
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | class Experiment { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  |   /// The City10000 dataset
 | 
					
						
							|  |  |  |   City10000Dataset dataset_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   // Parameters with default values
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  |   size_t maxLoopCount = 8000; | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 3000: {1: 62s, 2: 21s, 3: 20s, 4: 31s, 5: 39s} No DT optimizations
 | 
					
						
							|  |  |  |   // 3000: {1: 65s, 2: 20s, 3: 16s, 4: 21s, 5: 28s} With DT optimizations
 | 
					
						
							|  |  |  |   // 3000: {1: 59s, 2: 19s, 3: 18s, 4: 26s, 5: 33s} With DT optimizations +
 | 
					
						
							|  |  |  |   // merge
 | 
					
						
							|  |  |  |   size_t updateFrequency = 3; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   size_t maxNrHypotheses = 10; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |   size_t reLinearizationFrequency = 10; | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-03 01:06:40 +08:00
										 |  |  |   double marginalThreshold = 0.9999; | 
					
						
							| 
									
										
										
										
											2025-02-01 15:52:43 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |  private: | 
					
						
							|  |  |  |   HybridSmoother smoother_; | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |   HybridNonlinearFactorGraph newFactors_, allFactors_; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |   Values initial_; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * @brief Create a hybrid loop closure factor where | 
					
						
							|  |  |  |    * 0 - loose noise model and 1 - loop noise model. | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |   HybridNonlinearFactor hybridLoopClosureFactor( | 
					
						
							|  |  |  |       size_t loopCounter, size_t keyS, size_t keyT, | 
					
						
							|  |  |  |       const Pose2& measurement) const { | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     DiscreteKey l(L(loopCounter), 2); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     auto f0 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-01-30 13:23:17 +08:00
										 |  |  |         X(keyS), X(keyT), measurement, kOpenLoopModel); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     auto f1 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |         X(keyS), X(keyT), measurement, kPoseNoiseModel); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |     std::vector<NonlinearFactorValuePair> factors{{f0, kOpenLoopConstant}, | 
					
						
							|  |  |  |                                                   {f1, kPoseNoiseConstant}}; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     HybridNonlinearFactor mixtureFactor(l, factors); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     return mixtureFactor; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |   /// @brief Create hybrid odometry factor with discrete measurement choices.
 | 
					
						
							|  |  |  |   HybridNonlinearFactor hybridOdometryFactor( | 
					
						
							|  |  |  |       size_t numMeasurements, size_t keyS, size_t keyT, const DiscreteKey& m, | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |       const std::vector<Pose2>& poseArray) const { | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     auto f0 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |         X(keyS), X(keyT), poseArray[0], kPoseNoiseModel); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     auto f1 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |         X(keyS), X(keyT), poseArray[1], kPoseNoiseModel); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |     std::vector<NonlinearFactorValuePair> factors{{f0, kPoseNoiseConstant}, | 
					
						
							|  |  |  |                                                   {f1, kPoseNoiseConstant}}; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     HybridNonlinearFactor mixtureFactor(m, factors); | 
					
						
							|  |  |  |     return mixtureFactor; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |   /// @brief Perform smoother update and optimize the graph.
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  |   clock_t smootherUpdate(size_t maxNrHypotheses) { | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |     std::cout << "Smoother update: " << newFactors_.size() << std::endl; | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     gttic_(SmootherUpdate); | 
					
						
							|  |  |  |     clock_t beforeUpdate = clock(); | 
					
						
							|  |  |  |     auto linearized = newFactors_.linearize(initial_); | 
					
						
							|  |  |  |     smoother_.update(*linearized, maxNrHypotheses); | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |     allFactors_.push_back(newFactors_); | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     newFactors_.resize(0); | 
					
						
							|  |  |  |     clock_t afterUpdate = clock(); | 
					
						
							|  |  |  |     return afterUpdate - beforeUpdate; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |   /// @brief Re-linearize, solve ALL, and re-initialize smoother.
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  |   clock_t reInitialize() { | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |     std::cout << "================= Re-Initialize: " << allFactors_.size() | 
					
						
							|  |  |  |               << std::endl; | 
					
						
							|  |  |  |     clock_t beforeUpdate = clock(); | 
					
						
							|  |  |  |     allFactors_ = allFactors_.restrict(smoother_.fixedValues()); | 
					
						
							|  |  |  |     auto linearized = allFactors_.linearize(initial_); | 
					
						
							|  |  |  |     auto bayesNet = linearized->eliminateSequential(); | 
					
						
							|  |  |  |     HybridValues delta = bayesNet->optimize(); | 
					
						
							|  |  |  |     initial_ = initial_.retract(delta.continuous()); | 
					
						
							| 
									
										
										
										
											2025-02-10 00:41:47 +08:00
										 |  |  |     smoother_.reInitialize(std::move(*bayesNet)); | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |     clock_t afterUpdate = clock(); | 
					
						
							|  |  |  |     std::cout << "Took " << (afterUpdate - beforeUpdate) / CLOCKS_PER_SEC | 
					
						
							|  |  |  |               << " seconds." << std::endl; | 
					
						
							|  |  |  |     return afterUpdate - beforeUpdate; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   /// Construct with filename of experiment to run
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |   explicit Experiment(const std::string& filename) | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  |       : dataset_(filename), smoother_(marginalThreshold) {} | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// @brief Run the main experiment with a given maxLoopCount.
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |   void run() { | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Initialize local variables
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     size_t discreteCount = 0, index = 0, loopCount = 0, updateCount = 0; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     std::list<double> timeList; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Set up initial prior
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     Pose2 priorPose(0, 0, 0); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     initial_.insert(X(0), priorPose); | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     newFactors_.push_back( | 
					
						
							|  |  |  |         PriorFactor<Pose2>(X(0), priorPose, kPriorNoiseModel)); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Initial update
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     auto time = smootherUpdate(maxNrHypotheses); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     std::vector<std::pair<size_t, double>> smootherUpdateTimes; | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     smootherUpdateTimes.push_back({index, time}); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-31 13:14:05 +08:00
										 |  |  |     // Flag to decide whether to run smoother update
 | 
					
						
							|  |  |  |     size_t numberOfHybridFactors = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Start main loop
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     Values result; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     size_t keyS = 0, keyT = 0; | 
					
						
							|  |  |  |     clock_t startTime = clock(); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:24:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     std::vector<Pose2> poseArray; | 
					
						
							|  |  |  |     std::pair<size_t, size_t> keys; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) { | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |       keyS = keys.first; | 
					
						
							|  |  |  |       keyT = keys.second; | 
					
						
							|  |  |  |       size_t numMeasurements = poseArray.size(); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |       // Take the first one as the initial estimate
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |       Pose2 odomPose = poseArray[0]; | 
					
						
							|  |  |  |       if (keyS == keyT - 1) { | 
					
						
							|  |  |  |         // Odometry factor
 | 
					
						
							|  |  |  |         if (numMeasurements > 1) { | 
					
						
							|  |  |  |           // Add hybrid factor
 | 
					
						
							|  |  |  |           DiscreteKey m(M(discreteCount), numMeasurements); | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |           HybridNonlinearFactor mixtureFactor = | 
					
						
							|  |  |  |               hybridOdometryFactor(numMeasurements, keyS, keyT, m, poseArray); | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |           newFactors_.push_back(mixtureFactor); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |           discreteCount++; | 
					
						
							| 
									
										
										
										
											2025-01-31 13:14:05 +08:00
										 |  |  |           numberOfHybridFactors += 1; | 
					
						
							| 
									
										
										
										
											2025-01-30 06:54:04 +08:00
										 |  |  |           std::cout << "mixtureFactor: " << keyS << " " << keyT << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |         } else { | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |           newFactors_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, | 
					
						
							|  |  |  |                                                kPoseNoiseModel)); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |         // Insert next pose initial guess
 | 
					
						
							|  |  |  |         initial_.insert(X(keyT), initial_.at<Pose2>(X(keyS)) * odomPose); | 
					
						
							|  |  |  |       } else { | 
					
						
							|  |  |  |         // Loop closure
 | 
					
						
							|  |  |  |         HybridNonlinearFactor loopFactor = | 
					
						
							|  |  |  |             hybridLoopClosureFactor(loopCount, keyS, keyT, odomPose); | 
					
						
							| 
									
										
										
										
											2025-01-30 06:54:04 +08:00
										 |  |  |         // print loop closure event keys:
 | 
					
						
							|  |  |  |         std::cout << "Loop closure: " << keyS << " " << keyT << std::endl; | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |         newFactors_.add(loopFactor); | 
					
						
							| 
									
										
										
										
											2025-01-31 13:14:05 +08:00
										 |  |  |         numberOfHybridFactors += 1; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |         loopCount++; | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |       if (numberOfHybridFactors >= updateFrequency) { | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |         auto time = smootherUpdate(maxNrHypotheses); | 
					
						
							|  |  |  |         smootherUpdateTimes.push_back({index, time}); | 
					
						
							| 
									
										
										
										
											2025-01-31 13:14:05 +08:00
										 |  |  |         numberOfHybridFactors = 0; | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |         updateCount++; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         if (updateCount % reLinearizationFrequency == 0) { | 
					
						
							| 
									
										
										
										
											2025-02-01 15:29:08 +08:00
										 |  |  |           reInitialize(); | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |       // Record timing for odometry edges only
 | 
					
						
							|  |  |  |       if (keyS == keyT - 1) { | 
					
						
							|  |  |  |         clock_t curTime = clock(); | 
					
						
							|  |  |  |         timeList.push_back(curTime - startTime); | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // Print some status every 100 steps
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |       if (index % 100 == 0) { | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |         std::cout << "Index: " << index << std::endl; | 
					
						
							|  |  |  |         if (!timeList.empty()) { | 
					
						
							|  |  |  |           std::cout << "Acc_time: " << timeList.back() / CLOCKS_PER_SEC | 
					
						
							|  |  |  |                     << " seconds" << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-30 06:54:04 +08:00
										 |  |  |           // delta.discrete().print("The Discrete Assignment");
 | 
					
						
							|  |  |  |           tictoc_finishedIteration_(); | 
					
						
							|  |  |  |           tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |       index++; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Final update
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     time = smootherUpdate(maxNrHypotheses); | 
					
						
							|  |  |  |     smootherUpdateTimes.push_back({index, time}); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Final optimize
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     gttic_(HybridSmootherOptimize); | 
					
						
							| 
									
										
										
										
											2025-01-30 23:57:56 +08:00
										 |  |  |     HybridValues delta = smoother_.optimize(); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |     gttoc_(HybridSmootherOptimize); | 
					
						
							| 
									
										
										
										
											2025-01-30 23:57:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     result.insert_or_assign(initial_.retract(delta.continuous())); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     std::cout << "Final error: " << smoother_.hybridBayesNet().error(delta) | 
					
						
							|  |  |  |               << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     clock_t endTime = clock(); | 
					
						
							|  |  |  |     clock_t totalTime = endTime - startTime; | 
					
						
							|  |  |  |     std::cout << "Total time: " << totalTime / CLOCKS_PER_SEC << " seconds" | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  |               << std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Write results to file
 | 
					
						
							| 
									
										
										
										
											2025-02-01 11:33:55 +08:00
										 |  |  |     writeResult(result, keyT + 1, "Hybrid_City10000.txt"); | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     // Write timing info to file
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |     std::ofstream outfileTime; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     std::string timeFileName = "Hybrid_City10000_time.txt"; | 
					
						
							|  |  |  |     outfileTime.open(timeFileName); | 
					
						
							|  |  |  |     for (auto accTime : timeList) { | 
					
						
							|  |  |  |       outfileTime << accTime << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |     outfileTime.close(); | 
					
						
							|  |  |  |     std::cout << "Output " << timeFileName << " file." << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:31:32 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  | // Function to parse command-line arguments
 | 
					
						
							|  |  |  | void parseArguments(int argc, char* argv[], size_t& maxLoopCount, | 
					
						
							|  |  |  |                     size_t& updateFrequency, size_t& maxNrHypotheses) { | 
					
						
							|  |  |  |   for (int i = 1; i < argc; ++i) { | 
					
						
							|  |  |  |     std::string arg = argv[i]; | 
					
						
							|  |  |  |     if (arg == "--max-loop-count" && i + 1 < argc) { | 
					
						
							|  |  |  |       maxLoopCount = std::stoul(argv[++i]); | 
					
						
							|  |  |  |     } else if (arg == "--update-frequency" && i + 1 < argc) { | 
					
						
							|  |  |  |       updateFrequency = std::stoul(argv[++i]); | 
					
						
							|  |  |  |     } else if (arg == "--max-nr-hypotheses" && i + 1 < argc) { | 
					
						
							|  |  |  |       maxNrHypotheses = std::stoul(argv[++i]); | 
					
						
							|  |  |  |     } else if (arg == "--help") { | 
					
						
							|  |  |  |       std::cout << "Usage: " << argv[0] << " [options]\n" | 
					
						
							|  |  |  |                 << "Options:\n" | 
					
						
							|  |  |  |                 << "  --max-loop-count <value>       Set the maximum loop " | 
					
						
							|  |  |  |                    "count (default: 3000)\n" | 
					
						
							|  |  |  |                 << "  --update-frequency <value>     Set the update frequency " | 
					
						
							|  |  |  |                    "(default: 3)\n" | 
					
						
							|  |  |  |                 << "  --max-nr-hypotheses <value>    Set the maximum number of " | 
					
						
							|  |  |  |                    "hypotheses (default: 10)\n" | 
					
						
							|  |  |  |                 << "  --help                         Show this help message\n"; | 
					
						
							|  |  |  |       std::exit(0); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Main function
 | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  |   Experiment experiment(findExampleDataFile("T1_city10000_04.txt")); | 
					
						
							|  |  |  |   // Experiment experiment("../data/mh_T1_city10000_04.txt"); //Type #1 only
 | 
					
						
							|  |  |  |   // Experiment experiment("../data/mh_T3b_city10000_10.txt"); //Type #3 only
 | 
					
						
							| 
									
										
										
										
											2025-01-30 06:54:04 +08:00
										 |  |  |   // Experiment experiment("../data/mh_T1_T3_city10000_04.txt"); //Type #1 +
 | 
					
						
							|  |  |  |   // Type #3
 | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |   // Parse command-line arguments
 | 
					
						
							|  |  |  |   parseArguments(argc, argv, experiment.maxLoopCount, | 
					
						
							|  |  |  |                  experiment.updateFrequency, experiment.maxNrHypotheses); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-30 06:54:04 +08:00
										 |  |  |   // Run the experiment
 | 
					
						
							| 
									
										
										
										
											2025-02-01 04:47:42 +08:00
										 |  |  |   experiment.run(); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2025-01-29 10:42:11 +08:00
										 |  |  | } |