| 
									
										
										
										
											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>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/algorithm/string/classification.hpp>
 | 
					
						
							|  |  |  | #include <boost/algorithm/string/split.hpp>
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace boost::algorithm; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Testing params
 | 
					
						
							| 
									
										
										
										
											2025-01-30 07:40:29 +08:00
										 |  |  | const size_t max_loop_count = 2000;  // 2000;  // 200 //2000 //8000
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | noiseModel::Diagonal::shared_ptr prior_noise_model = | 
					
						
							|  |  |  |     noiseModel::Diagonal::Sigmas( | 
					
						
							|  |  |  |         (Vector(3) << 0.0001, 0.0001, 0.0001).finished()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | noiseModel::Diagonal::shared_ptr pose_noise_model = | 
					
						
							|  |  |  |     noiseModel::Diagonal::Sigmas( | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |         (Vector(3) << 1.0 / 30.0, 1.0 / 30.0, 1.0 / 100.0).finished()); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |  * @brief Write the result of optimization to filename. | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |  * | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |  * @param result The Values object with the final result. | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |  * @param num_poses The number of poses to write to the file. | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |  * @param filename The file name to save the result to. | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |  */ | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  | void write_result(const Values& result, size_t num_poses, | 
					
						
							|  |  |  |                   const std::string& filename = "Hybrid_city10000.txt") { | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   ofstream outfile; | 
					
						
							|  |  |  |   outfile.open(filename); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   for (size_t i = 0; i < num_poses; ++i) { | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |     Pose2 out_pose = result.at<Pose2>(X(i)); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |     outfile << out_pose.x() << " " << out_pose.y() << " " << out_pose.theta() | 
					
						
							|  |  |  |             << std::endl; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   outfile.close(); | 
					
						
							|  |  |  |   std::cout << "output written to " << filename << std::endl; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @brief Create a hybrid loop closure factor where | 
					
						
							|  |  |  |  * 0 - loose noise model and 1 - loop noise model. | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * @param loop_counter | 
					
						
							|  |  |  |  * @param key_s | 
					
						
							|  |  |  |  * @param key_t | 
					
						
							|  |  |  |  * @param measurement | 
					
						
							|  |  |  |  * @return HybridNonlinearFactor | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | HybridNonlinearFactor HybridLoopClosureFactor(size_t loop_counter, size_t key_s, | 
					
						
							|  |  |  |                                               size_t key_t, | 
					
						
							|  |  |  |                                               const Pose2& measurement) { | 
					
						
							|  |  |  |   DiscreteKey l(L(loop_counter), 2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   auto f0 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |       X(key_s), X(key_t), measurement, | 
					
						
							| 
									
										
										
										
											2025-01-30 03:13:39 +08:00
										 |  |  |       noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10)); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |   auto f1 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |       X(key_s), X(key_t), measurement, pose_noise_model); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |   std::vector<NonlinearFactorValuePair> factors{{f0, 0.0}, {f1, 0.0}}; | 
					
						
							|  |  |  |   HybridNonlinearFactor mixtureFactor(l, {f0, f1}); | 
					
						
							|  |  |  |   return mixtureFactor; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | HybridNonlinearFactor HybridOdometryFactor( | 
					
						
							|  |  |  |     size_t num_measurements, size_t key_s, size_t key_t, const DiscreteKey& m, | 
					
						
							|  |  |  |     const std::vector<Pose2>& pose_array, | 
					
						
							|  |  |  |     const SharedNoiseModel& pose_noise_model) { | 
					
						
							|  |  |  |   auto f0 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							|  |  |  |       X(key_s), X(key_t), pose_array[0], pose_noise_model); | 
					
						
							|  |  |  |   auto f1 = std::make_shared<BetweenFactor<Pose2>>( | 
					
						
							|  |  |  |       X(key_s), X(key_t), pose_array[1], pose_noise_model); | 
					
						
							|  |  |  |   std::vector<NonlinearFactorValuePair> factors{{f0, 0.0}, {f1, 0.0}}; | 
					
						
							|  |  |  |   HybridNonlinearFactor mixtureFactor(m, factors); | 
					
						
							|  |  |  |   // HybridNonlinearFactor mixtureFactor(m, {f0, f1});
 | 
					
						
							|  |  |  |   return mixtureFactor; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  | void SmootherUpdate(HybridSmoother& smoother, HybridNonlinearFactorGraph& graph, | 
					
						
							|  |  |  |                     const Values& initial, size_t maxNrHypotheses, | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |                     Values* result) { | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  |   HybridGaussianFactorGraph linearized = *graph.linearize(initial); | 
					
						
							|  |  |  |   // std::cout << "index: " << index << std::endl;
 | 
					
						
							|  |  |  |   smoother.update(linearized, maxNrHypotheses); | 
					
						
							|  |  |  |   graph.resize(0); | 
					
						
							| 
									
										
										
										
											2025-01-30 07:40:29 +08:00
										 |  |  |   // HybridValues delta = smoother.hybridBayesNet().optimize();
 | 
					
						
							|  |  |  |   // result->insert_or_assign(initial.retract(delta.continuous()));
 | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   ifstream in(findExampleDataFile("T1_city10000_04.txt")); | 
					
						
							|  |  |  |   // ifstream in("../data/mh_T1_city10000_04.txt"); //Type #1 only
 | 
					
						
							|  |  |  |   // ifstream in("../data/mh_T3b_city10000_10.txt"); //Type #3 only
 | 
					
						
							|  |  |  |   // ifstream in("../data/mh_T1_T3_city10000_04.txt"); //Type #1 + Type #3
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // ifstream in("../data/mh_All_city10000_groundtruth.txt");
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 02:43:56 +08:00
										 |  |  |   size_t discrete_count = 0, index = 0; | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |   size_t loop_count = 0; | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  |   size_t nrHybridFactors = 0; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   std::list<double> time_list; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 05:22:49 +08:00
										 |  |  |   HybridSmoother smoother(0.99); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |   HybridNonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   Values initial, result; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |   size_t maxNrHypotheses = 3; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   double x = 0.0; | 
					
						
							|  |  |  |   double y = 0.0; | 
					
						
							|  |  |  |   double rad = 0.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Pose2 prior_pose(x, y, rad); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   initial.insert(X(0), prior_pose); | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   graph.push_back(PriorFactor<Pose2>(X(0), prior_pose, prior_noise_model)); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |   std::vector<std::pair<size_t, double>> smoother_update_times; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   clock_t before_update = clock(); | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result); | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |   clock_t after_update = clock(); | 
					
						
							|  |  |  |   smoother_update_times.push_back({index, after_update - before_update}); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 10:23:09 +08:00
										 |  |  |   size_t key_s, key_t{0}; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   clock_t start_time = clock(); | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |   std::string str; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   while (getline(in, str) && index < max_loop_count) { | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     vector<string> parts; | 
					
						
							|  |  |  |     split(parts, str, is_any_of(" ")); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     key_s = stoi(parts[1]); | 
					
						
							|  |  |  |     key_t = stoi(parts[3]); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     int num_measurements = stoi(parts[5]); | 
					
						
							|  |  |  |     vector<Pose2> pose_array(num_measurements); | 
					
						
							|  |  |  |     for (int i = 0; i < num_measurements; ++i) { | 
					
						
							|  |  |  |       x = stod(parts[6 + 3 * i]); | 
					
						
							|  |  |  |       y = stod(parts[7 + 3 * i]); | 
					
						
							|  |  |  |       rad = stod(parts[8 + 3 * i]); | 
					
						
							|  |  |  |       pose_array[i] = Pose2(x, y, rad); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  |     // Flag if we should run smoother update
 | 
					
						
							|  |  |  |     bool smoother_update = false; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |     // Take the first one as the initial estimate
 | 
					
						
							|  |  |  |     Pose2 odom_pose = pose_array[0]; | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  |     if (key_s == key_t - 1) {  // odometry
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       if (num_measurements > 1) { | 
					
						
							|  |  |  |         DiscreteKey m(M(discrete_count), num_measurements); | 
					
						
							| 
									
										
										
										
											2025-01-24 02:43:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |         // Add hybrid factor which considers both measurements
 | 
					
						
							|  |  |  |         HybridNonlinearFactor mixtureFactor = HybridOdometryFactor( | 
					
						
							|  |  |  |             num_measurements, key_s, key_t, m, pose_array, pose_noise_model); | 
					
						
							|  |  |  |         graph.push_back(mixtureFactor); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |         discrete_count++; | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |         smoother_update = true; | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       } else { | 
					
						
							|  |  |  |         graph.add(BetweenFactor<Pose2>(X(key_s), X(key_t), odom_pose, | 
					
						
							|  |  |  |                                        pose_noise_model)); | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |       initial.insert(X(key_t), initial.at<Pose2>(X(key_s)) * odom_pose); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     } else {  // loop
 | 
					
						
							|  |  |  |       HybridNonlinearFactor loop_factor = | 
					
						
							|  |  |  |           HybridLoopClosureFactor(loop_count, key_s, key_t, odom_pose); | 
					
						
							|  |  |  |       graph.add(loop_factor); | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  |       smoother_update = true; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       loop_count++; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  |     if (smoother_update) { | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       gttic_(SmootherUpdate); | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |       before_update = clock(); | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |       SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result); | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |       after_update = clock(); | 
					
						
							|  |  |  |       smoother_update_times.push_back({index, after_update - before_update}); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       gttoc_(SmootherUpdate); | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |     // Print loop index and time taken in processor clock ticks
 | 
					
						
							| 
									
										
										
										
											2025-01-26 23:44:51 +08:00
										 |  |  |     // if (index % 50 == 0 && key_s != key_t - 1) {
 | 
					
						
							|  |  |  |     if (index % 100 == 0) { | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |       std::cout << "index: " << index << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  |       std::cout << "acc_time:  " << time_list.back() / CLOCKS_PER_SEC | 
					
						
							|  |  |  |                 << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  |       // delta.discrete().print("The Discrete Assignment");
 | 
					
						
							| 
									
										
										
										
											2025-01-24 10:54:57 +08:00
										 |  |  |       tictoc_finishedIteration_(); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |       tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     if (key_s == key_t - 1) { | 
					
						
							|  |  |  |       clock_t cur_time = clock(); | 
					
						
							|  |  |  |       time_list.push_back(cur_time - start_time); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-24 01:52:45 +08:00
										 |  |  |     index += 1; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |   before_update = clock(); | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result); | 
					
						
							| 
									
										
										
										
											2025-01-29 05:10:20 +08:00
										 |  |  |   after_update = clock(); | 
					
						
							|  |  |  |   smoother_update_times.push_back({index, after_update - before_update}); | 
					
						
							| 
									
										
										
										
											2025-01-25 01:30:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |   gttic_(HybridSmootherOptimize); | 
					
						
							|  |  |  |   HybridValues delta = smoother.hybridBayesNet().optimize(); | 
					
						
							|  |  |  |   gttoc_(HybridSmootherOptimize); | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   result.insert_or_assign(initial.retract(delta.continuous())); | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   std::cout << "Final error: " << smoother.hybridBayesNet().error(delta) | 
					
						
							|  |  |  |             << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   clock_t end_time = clock(); | 
					
						
							|  |  |  |   clock_t total_time = end_time - start_time; | 
					
						
							| 
									
										
										
										
											2025-01-25 01:09:30 +08:00
										 |  |  |   cout << "total_time: " << total_time / CLOCKS_PER_SEC << " seconds" << endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-28 17:18:19 +08:00
										 |  |  |   /// Write result to file
 | 
					
						
							|  |  |  |   write_result(result, (key_t + 1), "Hybrid_City10000.txt"); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-30 03:13:39 +08:00
										 |  |  |   // TODO Write to file
 | 
					
						
							|  |  |  |   //  for (size_t i = 0; i < smoother_update_times.size(); i++) {
 | 
					
						
							|  |  |  |   //    auto p = smoother_update_times.at(i);
 | 
					
						
							|  |  |  |   //    std::cout << p.first << ", " << p.second / CLOCKS_PER_SEC << std::endl;
 | 
					
						
							|  |  |  |   //  }
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   ofstream outfile_time; | 
					
						
							| 
									
										
										
										
											2025-01-28 12:17:52 +08:00
										 |  |  |   std::string time_file_name = "Hybrid_City10000_time.txt"; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   outfile_time.open(time_file_name); | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   for (auto acc_time : time_list) { | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |     outfile_time << acc_time << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   outfile_time.close(); | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  |   cout << "output " << time_file_name << " file." << endl; | 
					
						
							| 
									
										
										
										
											2025-01-28 05:35:50 +08:00
										 |  |  |   std::cout << nrHybridFactors << std::endl; | 
					
						
							| 
									
										
										
										
											2025-01-23 14:04:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2025-01-23 08:55:50 +08:00
										 |  |  |   return 0; | 
					
						
							|  |  |  | } |