update hybrid City10000 example

release/4.3a0
Varun Agrawal 2025-01-30 20:51:32 -05:00
parent b6e3b18776
commit 39ee58a962
1 changed files with 232 additions and 206 deletions

View File

@ -43,247 +43,273 @@ using symbol_shorthand::L;
using symbol_shorthand::M; using symbol_shorthand::M;
using symbol_shorthand::X; using symbol_shorthand::X;
// Testing params const size_t kMaxLoopCount = 2000; // Example default value
const size_t max_loop_count = 2000; // 2000; // 200 //2000 //8000 const size_t kMaxNrHypotheses = 10;
noiseModel::Diagonal::shared_ptr prior_noise_model = auto kOpenLoopModel = noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10);
noiseModel::Diagonal::Sigmas(
(Vector(3) << 0.0001, 0.0001, 0.0001).finished());
noiseModel::Diagonal::shared_ptr pose_noise_model = auto kPriorNoiseModel = noiseModel::Diagonal::Sigmas(
noiseModel::Diagonal::Sigmas( (Vector(3) << 0.0001, 0.0001, 0.0001).finished());
(Vector(3) << 1.0 / 30.0, 1.0 / 30.0, 1.0 / 100.0).finished());
/** auto kPoseNoiseModel = noiseModel::Diagonal::Sigmas(
* @brief Write the result of optimization to filename. (Vector(3) << 1.0 / 30.0, 1.0 / 30.0, 1.0 / 100.0).finished());
*
* @param result The Values object with the final result.
* @param num_poses The number of poses to write to the file.
* @param filename The file name to save the result to.
*/
void write_result(const Values& result, size_t num_poses,
const std::string& filename = "Hybrid_city10000.txt") {
ofstream outfile;
outfile.open(filename);
for (size_t i = 0; i < num_poses; ++i) { // Experiment Class
Pose2 out_pose = result.at<Pose2>(X(i)); class Experiment {
private:
std::string filename_;
HybridSmoother smoother_;
HybridNonlinearFactorGraph graph_;
Values initial_;
Values result_;
outfile << out_pose.x() << " " << out_pose.y() << " " << out_pose.theta() /**
<< std::endl; * @brief Write the result of optimization to file.
*
* @param result The Values object with the final result.
* @param num_poses The number of poses to write to the file.
* @param filename The file name to save the result to.
*/
void writeResult(const Values& result, size_t numPoses,
const std::string& filename = "Hybrid_city10000.txt") {
ofstream outfile;
outfile.open(filename);
for (size_t i = 0; i < numPoses; ++i) {
Pose2 outPose = result.at<Pose2>(X(i));
outfile << outPose.x() << " " << outPose.y() << " " << outPose.theta()
<< std::endl;
}
outfile.close();
std::cout << "Output written to " << filename << std::endl;
} }
outfile.close();
std::cout << "output written to " << filename << std::endl;
}
/** /**
* @brief Create a hybrid loop closure factor where * @brief Create a hybrid loop closure factor where
* 0 - loose noise model and 1 - loop noise model. * 0 - loose noise model and 1 - loop noise model.
* */
* @param loop_counter HybridNonlinearFactor hybridLoopClosureFactor(size_t loopCounter, size_t keyS,
* @param key_s size_t keyT,
* @param key_t const Pose2& measurement) {
* @param measurement DiscreteKey l(L(loopCounter), 2);
* @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 open_loop_model = noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10); auto f0 = std::make_shared<BetweenFactor<Pose2>>(
auto f0 = std::make_shared<BetweenFactor<Pose2>>( X(keyS), X(keyT), measurement, kOpenLoopModel);
X(key_s), X(key_t), measurement, open_loop_model); auto f1 = std::make_shared<BetweenFactor<Pose2>>(
auto f1 = std::make_shared<BetweenFactor<Pose2>>( X(keyS), X(keyT), measurement, kPoseNoiseModel);
X(key_s), X(key_t), measurement, pose_noise_model);
std::vector<NonlinearFactorValuePair> factors{
{f0, open_loop_model->negLogConstant()},
{f1, pose_noise_model->negLogConstant()}};
HybridNonlinearFactor mixtureFactor(l, {f0, f1});
return mixtureFactor;
}
HybridNonlinearFactor HybridOdometryFactor( std::vector<NonlinearFactorValuePair> factors{
size_t num_measurements, size_t key_s, size_t key_t, const DiscreteKey& m, {f0, kOpenLoopModel->negLogConstant()},
const std::vector<Pose2>& pose_array, {f1, kPoseNoiseModel->negLogConstant()}};
const SharedNoiseModel& pose_noise_model) { HybridNonlinearFactor mixtureFactor(l, factors);
auto f0 = std::make_shared<BetweenFactor<Pose2>>( return mixtureFactor;
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;
}
void SmootherUpdate(HybridSmoother& smoother, HybridNonlinearFactorGraph& graph, /// @brief Create hybrid odometry factor with discrete measurement choices.
const Values& initial, size_t maxNrHypotheses, HybridNonlinearFactor hybridOdometryFactor(
Values* result) { size_t numMeasurements, size_t keyS, size_t keyT, const DiscreteKey& m,
HybridGaussianFactorGraph linearized = *graph.linearize(initial); const std::vector<Pose2>& poseArray) {
smoother.update(linearized, maxNrHypotheses); auto f0 = std::make_shared<BetweenFactor<Pose2>>(
graph.resize(0); X(keyS), X(keyT), poseArray[0], kPoseNoiseModel);
// HybridValues delta = smoother.hybridBayesNet().optimize(); auto f1 = std::make_shared<BetweenFactor<Pose2>>(
// result->insert_or_assign(initial.retract(delta.continuous())); X(keyS), X(keyT), poseArray[1], kPoseNoiseModel);
}
/* ************************************************************************* */ std::vector<NonlinearFactorValuePair> factors{
int main(int argc, char* argv[]) { {f0, kPoseNoiseModel->negLogConstant()},
ifstream in(findExampleDataFile("T1_city10000_04.txt")); {f1, kPoseNoiseModel->negLogConstant()}};
// ifstream in("../data/mh_T1_city10000_04.txt"); //Type #1 only HybridNonlinearFactor mixtureFactor(m, factors);
// ifstream in("../data/mh_T3b_city10000_10.txt"); //Type #3 only return mixtureFactor;
// ifstream in("../data/mh_T1_T3_city10000_04.txt"); //Type #1 + Type #3 }
// ifstream in("../data/mh_All_city10000_groundtruth.txt"); /// @brief Perform smoother update and optimize the graph.
void smootherUpdate(HybridSmoother& smoother,
HybridNonlinearFactorGraph& graph, const Values& initial,
size_t kMaxNrHypotheses, Values* result) {
HybridGaussianFactorGraph linearized = *graph.linearize(initial);
smoother.update(linearized, kMaxNrHypotheses);
// throw if x0 not in hybridBayesNet_:
const KeySet& keys = smoother.hybridBayesNet().keys();
if (keys.find(X(0)) == keys.end()) {
throw std::runtime_error("x0 not in hybridBayesNet_");
}
graph.resize(0);
// HybridValues delta = smoother.hybridBayesNet().optimize();
// result->insert_or_assign(initial.retract(delta.continuous()));
}
size_t discrete_count = 0, index = 0; public:
size_t loop_count = 0; /// Construct with filename of experiment to run
size_t nrHybridFactors = 0; explicit Experiment(const std::string& filename)
: filename_(filename), smoother_(0.99) {}
std::list<double> time_list; /// @brief Run the main experiment with a given maxLoopCount.
void run(size_t maxLoopCount) {
HybridSmoother smoother(0.99); // Prepare reading
ifstream in(filename_);
HybridNonlinearFactorGraph graph; if (!in.is_open()) {
cerr << "Failed to open file: " << filename_ << endl;
Values initial, result; return;
size_t maxNrHypotheses = 3;
double x = 0.0;
double y = 0.0;
double rad = 0.0;
Pose2 prior_pose(x, y, rad);
initial.insert(X(0), prior_pose);
graph.push_back(PriorFactor<Pose2>(X(0), prior_pose, prior_noise_model));
std::vector<std::pair<size_t, double>> smoother_update_times;
clock_t before_update = clock();
SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result);
clock_t after_update = clock();
smoother_update_times.push_back({index, after_update - before_update});
size_t key_s, key_t{0};
clock_t start_time = clock();
std::string str;
while (getline(in, str) && index < max_loop_count) {
vector<string> parts;
split(parts, str, is_any_of(" "));
key_s = stoi(parts[1]);
key_t = stoi(parts[3]);
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);
} }
// Flag if we should run smoother update // Initialize local variables
bool smoother_update = false; size_t discreteCount = 0, index = 0;
size_t loopCount = 0;
// Take the first one as the initial estimate std::list<double> timeList;
Pose2 odom_pose = pose_array[0];
if (key_s == key_t - 1) { // odometry
if (num_measurements > 1) { // Set up initial prior
DiscreteKey m(M(discrete_count), num_measurements); double x = 0.0;
double y = 0.0;
double rad = 0.0;
// Add hybrid factor which considers both measurements Pose2 priorPose(x, y, rad);
HybridNonlinearFactor mixtureFactor = HybridOdometryFactor( initial_.insert(X(0), priorPose);
num_measurements, key_s, key_t, m, pose_array, pose_noise_model); graph_.push_back(PriorFactor<Pose2>(X(0), priorPose, kPriorNoiseModel));
graph.push_back(mixtureFactor);
discrete_count++; // Initial update
clock_t beforeUpdate = clock();
smootherUpdate(smoother_, graph_, initial_, kMaxNrHypotheses, &result_);
clock_t afterUpdate = clock();
std::vector<std::pair<size_t, double>> smootherUpdateTimes;
smootherUpdateTimes.push_back({index, afterUpdate - beforeUpdate});
smoother_update = true; // Start main loop
size_t keyS = 0, keyT = 0;
clock_t startTime = clock();
std::string line;
while (getline(in, line) && index < maxLoopCount) {
std::vector<std::string> parts;
split(parts, line, is_any_of(" "));
} else { keyS = stoi(parts[1]);
graph.add(BetweenFactor<Pose2>(X(key_s), X(key_t), odom_pose, keyT = stoi(parts[3]);
pose_noise_model));
int numMeasurements = stoi(parts[5]);
std::vector<Pose2> poseArray(numMeasurements);
for (int i = 0; i < numMeasurements; ++i) {
x = stod(parts[6 + 3 * i]);
y = stod(parts[7 + 3 * i]);
rad = stod(parts[8 + 3 * i]);
poseArray[i] = Pose2(x, y, rad);
} }
initial.insert(X(key_t), initial.at<Pose2>(X(key_s)) * odom_pose); // Flag to decide whether to run smoother update
bool doSmootherUpdate = false;
} else { // loop // Take the first one as the initial estimate
HybridNonlinearFactor loop_factor = Pose2 odomPose = poseArray[0];
HybridLoopClosureFactor(loop_count, key_s, key_t, odom_pose); if (keyS == keyT - 1) {
graph.add(loop_factor); // Odometry factor
if (numMeasurements > 1) {
// Add hybrid factor
DiscreteKey m(M(discreteCount), numMeasurements);
HybridNonlinearFactor mixtureFactor =
hybridOdometryFactor(numMeasurements, keyS, keyT, m, poseArray);
graph_.push_back(mixtureFactor);
discreteCount++;
doSmootherUpdate = true;
// std::cout << "mixtureFactor: " << keyS << " " << keyT << std::endl;
} else {
graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
kPoseNoiseModel));
}
// 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);
// print loop closure event keys:
// std::cout << "Loop closure: " << keyS << " " << keyT << std::endl;
graph_.add(loopFactor);
doSmootherUpdate = true;
loopCount++;
}
smoother_update = true; if (doSmootherUpdate) {
gttic_(SmootherUpdate);
beforeUpdate = clock();
smootherUpdate(smoother_, graph_, initial_, kMaxNrHypotheses, &result_);
afterUpdate = clock();
smootherUpdateTimes.push_back({index, afterUpdate - beforeUpdate});
gttoc_(SmootherUpdate);
doSmootherUpdate = false;
}
loop_count++; // 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
if (index % 100 == 0) {
std::cout << "Index: " << index << std::endl;
if (!timeList.empty()) {
std::cout << "Acc_time: " << timeList.back() / CLOCKS_PER_SEC
<< " seconds" << std::endl;
// delta.discrete().print("The Discrete Assignment");
tictoc_finishedIteration_();
tictoc_print_();
}
}
index++;
} }
if (smoother_update) { // Final update
gttic_(SmootherUpdate); beforeUpdate = clock();
before_update = clock(); smootherUpdate(smoother_, graph_, initial_, kMaxNrHypotheses, &result_);
SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result); afterUpdate = clock();
after_update = clock(); smootherUpdateTimes.push_back({index, afterUpdate - beforeUpdate});
smoother_update_times.push_back({index, after_update - before_update});
gttoc_(SmootherUpdate);
}
// Print loop index and time taken in processor clock ticks // Final optimize
// if (index % 50 == 0 && key_s != key_t - 1) { gttic_(HybridSmootherOptimize);
if (index % 100 == 0) { HybridValues delta = smoother_.optimize();
std::cout << "index: " << index << std::endl; gttoc_(HybridSmootherOptimize);
std::cout << "acc_time: " << time_list.back() / CLOCKS_PER_SEC
<< std::endl;
// delta.discrete().print("The Discrete Assignment");
tictoc_finishedIteration_();
tictoc_print_();
}
if (key_s == key_t - 1) { result_.insert_or_assign(initial_.retract(delta.continuous()));
clock_t cur_time = clock();
time_list.push_back(cur_time - start_time);
}
index += 1; std::cout << "Final error: " << smoother_.hybridBayesNet().error(delta)
<< std::endl;
clock_t endTime = clock();
clock_t totalTime = endTime - startTime;
std::cout << "Total time: " << totalTime / CLOCKS_PER_SEC << " seconds"
<< std::endl;
// Write results to file
writeResult(result_, keyT + 1, "Hybrid_City10000.txt");
// 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;
// }
// Write timing info to file
ofstream outfileTime;
std::string timeFileName = "Hybrid_City10000_time.txt";
outfileTime.open(timeFileName);
for (auto accTime : timeList) {
outfileTime << accTime << std::endl;
}
outfileTime.close();
std::cout << "Output " << timeFileName << " file." << std::endl;
} }
};
before_update = clock(); /* ************************************************************************* */
SmootherUpdate(smoother, graph, initial, maxNrHypotheses, &result); int main() {
after_update = clock(); Experiment experiment(findExampleDataFile("T1_city10000_04.txt"));
smoother_update_times.push_back({index, after_update - before_update}); // 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 +
// Type #3
gttic_(HybridSmootherOptimize); // Run the experiment
HybridValues delta = smoother.hybridBayesNet().optimize(); experiment.run(kMaxLoopCount);
gttoc_(HybridSmootherOptimize);
result.insert_or_assign(initial.retract(delta.continuous()));
std::cout << "Final error: " << smoother.hybridBayesNet().error(delta)
<< std::endl;
clock_t end_time = clock();
clock_t total_time = end_time - start_time;
cout << "total_time: " << total_time / CLOCKS_PER_SEC << " seconds" << endl;
/// Write result to file
write_result(result, (key_t + 1), "Hybrid_City10000.txt");
// 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;
// }
ofstream outfile_time;
std::string time_file_name = "Hybrid_City10000_time.txt";
outfile_time.open(time_file_name);
for (auto acc_time : time_list) {
outfile_time << acc_time << std::endl;
}
outfile_time.close();
cout << "output " << time_file_name << " file." << endl;
std::cout << nrHybridFactors << std::endl;
return 0; return 0;
} }