| 
									
										
										
										
											2025-01-23 14:04:20 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2025-02-01 15:00:33 +08:00
										 |  |  |  * @file   ISAM2_City10000.cpp | 
					
						
							|  |  |  |  * @brief  Example of using ISAM2 estimation | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |  *         with multiple odometry measurements. | 
					
						
							|  |  |  |  * @author Varun Agrawal | 
					
						
							|  |  |  |  * @date   January 22, 2025 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/ISAM2.h>
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  | #include <gtsam/nonlinear/ISAM2Params.h>
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <time.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/algorithm/string/classification.hpp>
 | 
					
						
							|  |  |  | #include <boost/algorithm/string/split.hpp>
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  | #include "City10000.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using symbol_shorthand::X; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | // Experiment Class
 | 
					
						
							|  |  |  | class Experiment { | 
					
						
							|  |  |  |   /// The City10000 dataset
 | 
					
						
							|  |  |  |   City10000Dataset dataset_; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   // Parameters with default values
 | 
					
						
							|  |  |  |   size_t maxLoopCount = 2000;  // 200 //2000 //8000
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |   // false: run original iSAM2 without ambiguities
 | 
					
						
							|  |  |  |   // true: run original iSAM2 with ambiguities
 | 
					
						
							| 
									
										
										
										
											2025-02-07 06:38:52 +08:00
										 |  |  |   bool isWithAmbiguity; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |  private: | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:49 +08:00
										 |  |  |   ISAM2 isam2_; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |   NonlinearFactorGraph graph_; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |   Values initial_; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   Values results; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |  public: | 
					
						
							|  |  |  |   /// Construct with filename of experiment to run
 | 
					
						
							| 
									
										
										
										
											2025-02-07 06:02:39 +08:00
										 |  |  |   explicit Experiment(const std::string& filename, bool isWithAmbiguity = false) | 
					
						
							| 
									
										
										
										
											2025-02-07 06:10:37 +08:00
										 |  |  |       : dataset_(filename), isWithAmbiguity(isWithAmbiguity) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:49 +08:00
										 |  |  |     ISAM2Params parameters; | 
					
						
							|  |  |  |     parameters.optimizationParams = gtsam::ISAM2GaussNewtonParams(0.0); | 
					
						
							|  |  |  |     parameters.relinearizeThreshold = 0.01; | 
					
						
							|  |  |  |     parameters.relinearizeSkip = 1; | 
					
						
							|  |  |  |     isam2_ = ISAM2(parameters); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// @brief Run the main experiment with a given maxLoopCount.
 | 
					
						
							|  |  |  |   void run() { | 
					
						
							|  |  |  |     // Initialize local variables
 | 
					
						
							| 
									
										
										
										
											2025-02-07 06:02:39 +08:00
										 |  |  |     size_t index = 0; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |     std::vector<std::pair<size_t, double>> smootherUpdateTimes; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |     std::list<double> timeList; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Set up initial prior
 | 
					
						
							|  |  |  |     Pose2 priorPose(0, 0, 0); | 
					
						
							|  |  |  |     initial_.insert(X(0), priorPose); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |     graph_.addPrior<Pose2>(X(0), priorPose, kPriorNoiseModel); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Initial update
 | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |     clock_t beforeUpdate = clock(); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |     isam2_.update(graph_, initial_); | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |     results = isam2_.calculateBestEstimate(); | 
					
						
							|  |  |  |     clock_t afterUpdate = clock(); | 
					
						
							|  |  |  |     smootherUpdateTimes.push_back( | 
					
						
							|  |  |  |         std::make_pair(index, afterUpdate - beforeUpdate)); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |     graph_.resize(0); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |     initial_.clear(); | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |     index += 1; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Start main loop
 | 
					
						
							|  |  |  |     size_t keyS = 0; | 
					
						
							|  |  |  |     size_t keyT = 0; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |     clock_t startTime = clock(); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:34:59 +08:00
										 |  |  |     std::vector<Pose2> poseArray; | 
					
						
							|  |  |  |     std::pair<size_t, size_t> keys; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     while (dataset_.next(&poseArray, &keys) && index < maxLoopCount) { | 
					
						
							|  |  |  |       keyS = keys.first; | 
					
						
							|  |  |  |       keyT = keys.second; | 
					
						
							|  |  |  |       size_t numMeasurements = poseArray.size(); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |       Pose2 odomPose; | 
					
						
							| 
									
										
										
										
											2025-02-07 06:10:37 +08:00
										 |  |  |       if (isWithAmbiguity) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |         // Get wrong intentionally
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         int id = index % numMeasurements; | 
					
						
							|  |  |  |         odomPose = Pose2(poseArray[id]); | 
					
						
							| 
									
										
										
										
											2025-01-30 23:58:46 +08:00
										 |  |  |       } else { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         odomPose = poseArray[0]; | 
					
						
							| 
									
										
										
										
											2025-01-30 23:58:46 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       if (keyS == keyT - 1) {  // new X(key)
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         initial_.insert(X(keyT), results.at<Pose2>(X(keyS)) * odomPose); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |         graph_.add( | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |             BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, kPoseNoiseModel)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       } else {  // loop
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         int id = index % numMeasurements; | 
					
						
							| 
									
										
										
										
											2025-02-07 06:10:37 +08:00
										 |  |  |         if (isWithAmbiguity && id % 2 == 0) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |           graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose, | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:49 +08:00
										 |  |  |                                           kPoseNoiseModel)); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |         } else { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |           graph_.add(BetweenFactor<Pose2>( | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |               X(keyS), X(keyT), odomPose, | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |               noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10.0))); | 
					
						
							|  |  |  |         } | 
					
						
							|  |  |  |         index++; | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |       clock_t beforeUpdate = clock(); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |       isam2_.update(graph_, initial_); | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |       results = isam2_.calculateBestEstimate(); | 
					
						
							|  |  |  |       clock_t afterUpdate = clock(); | 
					
						
							|  |  |  |       smootherUpdateTimes.push_back( | 
					
						
							|  |  |  |           std::make_pair(index, afterUpdate - beforeUpdate)); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:58:29 +08:00
										 |  |  |       graph_.resize(0); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       initial_.clear(); | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  |       index += 1; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       // Print loop index and time taken in processor clock ticks
 | 
					
						
							|  |  |  |       if (index % 50 == 0 && keyS != keyT - 1) { | 
					
						
							|  |  |  |         std::cout << "index: " << index << std::endl; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         std::cout << "accTime:  " << timeList.back() / CLOCKS_PER_SEC | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |                   << std::endl; | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       if (keyS == keyT - 1) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         clock_t curTime = clock(); | 
					
						
							|  |  |  |         timeList.push_back(curTime - startTime); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |       if (timeList.size() % 100 == 0 && (keyS == keyT - 1)) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |         std::string stepFileIdx = std::to_string(100000 + timeList.size()); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |         std::ofstream stepOutfile; | 
					
						
							|  |  |  |         std::string stepFileName = "step_files/ISAM2_City10000_S" + stepFileIdx; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         stepOutfile.open(stepFileName + ".txt"); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |         for (size_t i = 0; i < (keyT + 1); ++i) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |           Pose2 outPose = results.at<Pose2>(X(i)); | 
					
						
							|  |  |  |           stepOutfile << outPose.x() << " " << outPose.y() << " " | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |                       << outPose.theta() << std::endl; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |         } | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |         stepOutfile.close(); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |     clock_t endTime = clock(); | 
					
						
							|  |  |  |     clock_t totalTime = endTime - startTime; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |     std::cout << "totalTime: " << totalTime / CLOCKS_PER_SEC << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |     /// Write results to file
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:40:35 +08:00
										 |  |  |     writeResult(results, (keyT + 1), "ISAM2_City10000.txt"); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |     std::ofstream outfileTime; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:40:35 +08:00
										 |  |  |     std::string timeFileName = "ISAM2_City10000_time.txt"; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |     outfileTime.open(timeFileName); | 
					
						
							|  |  |  |     for (auto accTime : timeList) { | 
					
						
							|  |  |  |       outfileTime << accTime << std::endl; | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2025-02-07 05:39:49 +08:00
										 |  |  |     outfileTime.close(); | 
					
						
							| 
									
										
										
										
											2025-02-07 05:45:42 +08:00
										 |  |  |     std::cout << "Written cumulative time to: " << timeFileName << " file." | 
					
						
							|  |  |  |               << std::endl; | 
					
						
							| 
									
										
										
										
											2025-03-25 21:45:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     std::ofstream timingFile; | 
					
						
							|  |  |  |     std::string timingFileName = "ISAM2_City10000_timing.txt"; | 
					
						
							|  |  |  |     timingFile.open(timingFileName); | 
					
						
							|  |  |  |     for (size_t i = 0; i < smootherUpdateTimes.size(); i++) { | 
					
						
							|  |  |  |       auto p = smootherUpdateTimes.at(i); | 
					
						
							|  |  |  |       timingFile << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     timingFile.close(); | 
					
						
							|  |  |  |     std::cout << "Wrote timing information to " << timingFileName << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 06:10:37 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Function to parse command-line arguments
 | 
					
						
							|  |  |  | void parseArguments(int argc, char* argv[], size_t& maxLoopCount, | 
					
						
							|  |  |  |                     bool& isWithAmbiguity) { | 
					
						
							|  |  |  |   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 == "--is-with-ambiguity" && i + 1 < argc) { | 
					
						
							|  |  |  |       isWithAmbiguity = bool(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: 2000)\n" | 
					
						
							|  |  |  |                 << "  --is-with-ambiguity <value=0/1>     Set whether to use " | 
					
						
							|  |  |  |                    "ambiguous measurements " | 
					
						
							|  |  |  |                    "(default: false)\n" | 
					
						
							|  |  |  |                 << "  --help                         Show this help message\n"; | 
					
						
							|  |  |  |       std::exit(0); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							| 
									
										
										
										
											2025-02-07 05:40:35 +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
 | 
					
						
							|  |  |  |   // Experiment experiment("../data/mh_T1_T3_City10000_04.txt"); //Type #1 +
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |   // Type #3
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 06:10:37 +08:00
										 |  |  |   // Parse command-line arguments
 | 
					
						
							|  |  |  |   parseArguments(argc, argv, experiment.maxLoopCount, | 
					
						
							|  |  |  |                  experiment.isWithAmbiguity); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-02-07 05:32:24 +08:00
										 |  |  |   // Run the experiment
 | 
					
						
							|  |  |  |   experiment.run(); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |