58 {
59 if (argc < 2) {
60 cout << endl;
61 cout << "Please type: " << endl;
62 cout << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] "
63 "[STRUCTURE_ONLY] [DENSE]"
64 << endl;
65 cout << endl;
66 cout << "PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
67 cout << "OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
68 << endl;
69 cout << "ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
70 << endl;
71 cout << "STRUCTURE_ONLY: performed structure-only BA to get better point "
72 "initializations (0 or 1; default: 0==false)"
73 << endl;
74 cout << "DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
75 cout << endl;
76 cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
77 "1==true."
78 << endl;
79 cout << endl;
80 exit(0);
81 }
82
83 double PIXEL_NOISE = atof(argv[1]);
84 double OUTLIER_RATIO = 0.0;
85
86 if (argc > 2) {
87 OUTLIER_RATIO = atof(argv[2]);
88 }
89
90 bool ROBUST_KERNEL = false;
91 if (argc > 3) {
92 ROBUST_KERNEL = atoi(argv[3]) != 0;
93 }
94 bool STRUCTURE_ONLY = false;
95 if (argc > 4) {
96 STRUCTURE_ONLY = atoi(argv[4]) != 0;
97 }
98
99 bool DENSE = false;
100 if (argc > 5) {
101 DENSE = atoi(argv[5]) != 0;
102 }
103
104 cout << "PIXEL_NOISE: " << PIXEL_NOISE << endl;
105 cout << "OUTLIER_RATIO: " << OUTLIER_RATIO << endl;
106 cout << "ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
107 cout << "STRUCTURE_ONLY: " << STRUCTURE_ONLY << endl;
108 cout << "DENSE: " << DENSE << endl;
109
112 string solverName = "lm_fix6_3";
113 if (DENSE) {
114 solverName = "lm_dense6_3";
115 } else {
116#ifdef G2O_HAVE_CHOLMOD
117 solverName = "lm_fix6_3_cholmod";
118#else
119 solverName = "lm_fix6_3";
120#endif
121 }
122
126 solverProperty));
127
128 vector<Vector3d> true_points;
129 for (size_t i = 0; i < 500; ++i) {
130 true_points.push_back(
134 }
135
136 double focal_length = 1000.;
137 Vector2d principal_point(320., 240.);
138
139 vector<g2o::SE3Quat, aligned_allocator<g2o::SE3Quat> > true_poses;
142 cam_params->
setId(0);
143
145 assert(false);
146 }
147
148 int vertex_id = 0;
149 for (size_t i = 0; i < 15; ++i) {
150 Vector3d trans(i * 0.04 - 1., 0, 0);
151
152 Eigen::Quaterniond q;
153 q.setIdentity();
156 v_se3->
setId(vertex_id);
157 if (i < 2) {
159 }
162 true_poses.push_back(pose);
163 vertex_id++;
164 }
165 int point_id = vertex_id;
166 double sum_diff2 = 0;
167
168 cout << endl;
169 unordered_map<int, int> pointid_2_trueid;
170 unordered_set<int> inliers;
171
172 for (size_t i = 0; i < true_points.size(); ++i) {
174 v_p->
setId(point_id);
180 int num_obs = 0;
181 for (size_t j = 0; j < true_poses.size(); ++j) {
182 Vector2d z = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
183 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
184 ++num_obs;
185 }
186 }
187 if (num_obs >= 2) {
189 bool inlier = true;
190 for (size_t j = 0; j < true_poses.size(); ++j) {
191 Vector2d z =
192 cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
193
194 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
196 if (sam < OUTLIER_RATIO) {
198 inlier = false;
199 }
205 optimizer.
vertices().find(j)->second));
208 if (ROBUST_KERNEL) {
211 }
214 }
215 }
216
217 if (inlier) {
218 inliers.insert(point_id);
219 Vector3d diff = v_p->
estimate() - true_points[i];
220
221 sum_diff2 += diff.dot(diff);
222 }
223 pointid_2_trueid.insert(make_pair(point_id, i));
224 ++point_id;
225 }
226 }
227 cout << endl;
230 if (STRUCTURE_ONLY) {
232 cout << "Performing structure-only BA:" << endl;
234 for (g2o::OptimizableGraph::VertexIDMap::const_iterator it =
236 it != optimizer.
vertices().end(); ++it) {
239 if (v->
dimension() == 3) points.push_back(v);
240 }
241 structure_only_ba.
calc(points, 10);
242 }
243
244 cout << endl;
245 cout << "Performing full BA:" << endl;
247 cout << endl;
248 cout << "Point error before optimisation (inliers only): "
249 <<
sqrt(sum_diff2 / inliers.size()) << endl;
250 sum_diff2 = 0;
251 for (unordered_map<int, int>::iterator it = pointid_2_trueid.begin();
252 it != pointid_2_trueid.end(); ++it) {
253 g2o::HyperGraph::VertexIDMap::iterator v_it =
254 optimizer.
vertices().find(it->first);
255 if (v_it == optimizer.
vertices().end()) {
256 cerr << "Vertex " << it->first << " not in graph!" << endl;
257 exit(-1);
258 }
260 if (v_p == 0) {
261 cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
262 exit(-1);
263 }
264 Vector3d diff = v_p->
estimate() - true_points[it->second];
265 if (inliers.find(it->first) == inliers.end()) continue;
266 sum_diff2 += diff.dot(diff);
267 }
268 cout << "Point error after optimisation (inliers only): "
269 <<
sqrt(sum_diff2 / inliers.size()) << endl;
270 cout << endl;
271}
static int uniform(int from, int to)
virtual void setMeasurement(const Measurement &m)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Vector2 cam_map(const Vector3 &trans_xyz) const
void setVertex(size_t i, Vertex *v)
const VertexIDMap & vertices() const
void setRobustKernel(RobustKernel *ptr)
bool setParameterId(int argNum, int paramId)
A general case Vertex for optimization.
int dimension() const
dimension of the estimated state belonging to this node
virtual void setId(int id)
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
static OptimizationAlgorithmFactory * instance()
return the instance
static double gaussRand(double mean, double sigma)
static double uniformRand(double lowerBndr, double upperBndr)
int optimize(int iterations, bool online=false)
void setVerbose(bool verbose)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
void setAlgorithm(OptimizationAlgorithm *algorithm)
This is a solver for "structure-only" optimization".
OptimizationAlgorithm::SolverResult calc(OptimizableGraph::VertexContainer &vertices, int num_iters, int num_max_trials=10)
Vertex for a tracked point in space.
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
Jet< T, N > sqrt(const Jet< T, N > &f)
std::vector< OptimizableGraph::Vertex * > VertexContainer
vector container for vertices
virtual bool addEdge(HyperGraph::Edge *e)
bool addParameter(Parameter *p)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
describe the properties of a solver