diff options
author | Miller | 2017-07-06 01:31:42 -0500 |
---|---|---|
committer | Miller | 2017-07-06 01:31:42 -0500 |
commit | c43500dc7b87fdd852da23f4578c939c5f175a59 (patch) | |
tree | e8abf88145e7afc8c617404da99e9629561959cf /src | |
parent | 817f93fce0e8adbc55ea0f5603dabf0bd028e7ab (diff) | |
download | refslam-c43500dc7b87fdd852da23f4578c939c5f175a59.zip refslam-c43500dc7b87fdd852da23f4578c939c5f175a59.tar.gz |
set all params on cli
Diffstat (limited to 'src')
-rw-r--r-- | src/main.cpp | 22 |
1 files changed, 19 insertions, 3 deletions
diff --git a/src/main.cpp b/src/main.cpp index ebeb818..b72c0f1 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -39,7 +39,7 @@ double canoeheight = -0.46; double ransac_li_threshold = 1.8e-6; double ransac_hi_threshold = 0.25; -double covbias 2e-5; +double covbias = 2e-5; using std::cout; using std::endl; @@ -436,8 +436,8 @@ update_dt(const timestamp t, timestamp *t_old) int main(int argc, char **argv) { - if (argc!=2) { - fprintf(stderr, "Usage: %s camera\n", argv[0]); + if (argc!=3) { + fprintf(stderr, "Usage: %s camera params\n", argv[0]); exit(1); } State mu; @@ -467,6 +467,22 @@ main(int argc, char **argv) #endif #endif /* ----- not ROS_PUBLISH ----- */ // read params file + FILE *pfin; + pfin = fopen(argv[2], "r"); + fscanf(pfin,"%lf",&feature_noise); + fscanf(pfin,"%lf",&view_noise); + fscanf(pfin,"%lf",&initial_view_noise); + fscanf(pfin,"%lf",&reflection_view_noise); + fscanf(pfin,"%lf",&r_height); + fscanf(pfin,"%lf",&acc_std); + fscanf(pfin,"%lf",&ang_std); + fscanf(pfin,"%lf",&acc_bias_std); + fscanf(pfin,"%lf",&canoecenter); + fscanf(pfin,"%lf",&canoeheight); + fscanf(pfin,"%lf",&ransac_li_threshold); + fscanf(pfin,"%lf",&ransac_hi_threshold); + fscanf(pfin,"%lf",&covbias); + fclose(pfin); // Read sensors from file int i=0; char line[MAXLINE]; |