Skip to content

Commit f7b798e

Browse files
committed
parseArguments function
1 parent 54c603d commit f7b798e

File tree

1 file changed

+32
-4
lines changed

1 file changed

+32
-4
lines changed

examples/ISAM2_City10000.cpp

Lines changed: 32 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ class Experiment {
5050

5151
// false: run original iSAM2 without ambiguities
5252
// true: run original iSAM2 with ambiguities
53-
const bool isWithAmbiguity_;
53+
const bool isWithAmbiguity;
5454

5555
private:
5656
ISAM2 isam2_;
@@ -61,7 +61,7 @@ class Experiment {
6161
public:
6262
/// Construct with filename of experiment to run
6363
explicit Experiment(const std::string& filename, bool isWithAmbiguity = false)
64-
: dataset_(filename), isWithAmbiguity_(isWithAmbiguity) {
64+
: dataset_(filename), isWithAmbiguity(isWithAmbiguity) {
6565
ISAM2Params parameters;
6666
parameters.optimizationParams = gtsam::ISAM2GaussNewtonParams(0.0);
6767
parameters.relinearizeThreshold = 0.01;
@@ -101,7 +101,7 @@ class Experiment {
101101
size_t numMeasurements = poseArray.size();
102102

103103
Pose2 odomPose;
104-
if (isWithAmbiguity_) {
104+
if (isWithAmbiguity) {
105105
// Get wrong intentionally
106106
int id = index % numMeasurements;
107107
odomPose = Pose2(poseArray[id]);
@@ -116,7 +116,7 @@ class Experiment {
116116

117117
} else { // loop
118118
int id = index % numMeasurements;
119-
if (isWithAmbiguity_ && id % 2 == 0) {
119+
if (isWithAmbiguity && id % 2 == 0) {
120120
graph_.add(BetweenFactor<Pose2>(X(keyS), X(keyT), odomPose,
121121
kPoseNoiseModel));
122122
} else {
@@ -178,6 +178,30 @@ class Experiment {
178178
}
179179
};
180180

181+
/* ************************************************************************* */
182+
// Function to parse command-line arguments
183+
void parseArguments(int argc, char* argv[], size_t& maxLoopCount,
184+
bool& isWithAmbiguity) {
185+
for (int i = 1; i < argc; ++i) {
186+
std::string arg = argv[i];
187+
if (arg == "--max-loop-count" && i + 1 < argc) {
188+
maxLoopCount = std::stoul(argv[++i]);
189+
} else if (arg == "--is-with-ambiguity" && i + 1 < argc) {
190+
isWithAmbiguity = bool(std::stoul(argv[++i]));
191+
} else if (arg == "--help") {
192+
std::cout << "Usage: " << argv[0] << " [options]\n"
193+
<< "Options:\n"
194+
<< " --max-loop-count <value> Set the maximum loop "
195+
"count (default: 2000)\n"
196+
<< " --is-with-ambiguity <value=0/1> Set whether to use "
197+
"ambiguous measurements "
198+
"(default: false)\n"
199+
<< " --help Show this help message\n";
200+
std::exit(0);
201+
}
202+
}
203+
}
204+
181205
/* ************************************************************************* */
182206
int main(int argc, char* argv[]) {
183207
Experiment experiment(findExampleDataFile("T1_City10000_04.txt"));
@@ -186,6 +210,10 @@ int main(int argc, char* argv[]) {
186210
// Experiment experiment("../data/mh_T1_T3_City10000_04.txt"); //Type #1 +
187211
// Type #3
188212

213+
// Parse command-line arguments
214+
parseArguments(argc, argv, experiment.maxLoopCount,
215+
experiment.isWithAmbiguity);
216+
189217
// Run the experiment
190218
experiment.run();
191219

0 commit comments

Comments
 (0)