-
Notifications
You must be signed in to change notification settings - Fork 34
/
parameters.h
108 lines (86 loc) · 1.92 KB
/
parameters.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
//
// Created by grn on 11/2/18.
//
#ifndef VINS_PARAMETERS_H
#define VINS_PARAMETERS_H
#include <vector>
#include <eigen3/Eigen/Dense>
#include "utility/utility.h"
#include <opencv2/opencv.hpp>
#include <opencv2/core/eigen.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <fstream>
#include <string>
#include <iostream>
using namespace std;
extern double FOCAL_LENGTH;
const int WINDOW_SIZE = 11;
const int NUM_OF_CAM = 1;
const int NUM_OF_F = 1000;
// GPS
extern int GPS_HZ;
extern int is_out;
extern double out_start;
extern double out_end;
extern double GPS_L0;
extern double GPS_L1;
extern double GPS_L2;
//#define UNIT_SPHERE_ERROR
extern double INIT_DEPTH;
extern double MIN_PARALLAX;
extern int ESTIMATE_EXTRINSIC;
extern double ACC_N, ACC_W;
extern double GYR_N, GYR_W;
extern std::vector<Eigen::Matrix3d> RIC;
extern std::vector<Eigen::Vector3d> TIC;
extern Eigen::Vector3d G;
extern double BIAS_ACC_THRESHOLD;
extern double BIAS_GYR_THRESHOLD;
extern double SOLVER_TIME;
extern int NUM_ITERATIONS;
extern std::string EX_CALIB_RESULT_PATH;
extern std::string VINS_RESULT_PATH;
extern double TD;
extern double TR;
extern int ESTIMATE_TD;
extern int ROLLING_SHUTTER;
extern int ROW, COL;
//feature
extern std::string IMAGE_file;
extern std::string IMAGE_data;
extern std::string IMU_file;
extern std::string GPS_file;
extern std::string FISHEYE_MASK;
extern std::vector<std::string> CAM_NAMES;
extern int MAX_CNT;
extern int MIN_DIST;
extern int FREQ;
extern double F_THRESHOLD;
extern int SHOW_TRACK;
extern int STEREO_TRACK;
extern int EQUALIZE;
extern int FISHEYE;
extern bool PUB_THIS_FRAME;
void readParameters(std::string configfile);
enum SIZE_PARAMETERIZATION
{
SIZE_POSE = 7,
SIZE_SPEEDBIAS = 9,
SIZE_FEATURE = 1
};
enum StateOrder
{
O_P = 0,
O_R = 3,
O_V = 6,
O_BA = 9,
O_BG = 12
};
enum NoiseOrder
{
O_AN = 0,
O_GN = 3,
O_AW = 6,
O_GW = 9
};
#endif //VINS_PARAMETERS_H