58int main(
int argc,
const char* argv[]) {
61 cout <<
"Please type: " << endl;
62 cout <<
"ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] "
63 "[STRUCTURE_ONLY] [DENSE]"
66 cout <<
"PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
67 cout <<
"OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
69 cout <<
"ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
71 cout <<
"STRUCTURE_ONLY: performed structure-only BA to get better point "
72 "initializations (0 or 1; default: 0==false)"
74 cout <<
"DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
76 cout <<
"Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
83 double PIXEL_NOISE = atof(argv[1]);
84 double OUTLIER_RATIO = 0.0;
87 OUTLIER_RATIO = atof(argv[2]);
90 bool ROBUST_KERNEL =
false;
92 ROBUST_KERNEL = atoi(argv[3]) != 0;
94 bool STRUCTURE_ONLY =
false;
96 STRUCTURE_ONLY = atoi(argv[4]) != 0;
101 DENSE = atoi(argv[5]) != 0;
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;
112 string solverName =
"lm_fix6_3";
114 solverName =
"lm_dense6_3";
116#ifdef G2O_HAVE_CHOLMOD
117 solverName =
"lm_fix6_3_cholmod";
119 solverName =
"lm_fix6_3";
128 vector<Vector3d> true_points;
129 for (
size_t i = 0; i < 500; ++i) {
130 true_points.push_back(
136 double focal_length = 1000.;
137 Vector2d principal_point(320., 240.);
139 vector<g2o::SE3Quat, aligned_allocator<g2o::SE3Quat> > true_poses;
142 cam_params->
setId(0);
149 for (
size_t i = 0; i < 15; ++i) {
150 Vector3d trans(i * 0.04 - 1., 0, 0);
152 Eigen::Quaterniond q;
156 v_se3->
setId(vertex_id);
162 true_poses.push_back(pose);
165 int point_id = vertex_id;
166 double sum_diff2 = 0;
169 unordered_map<int, int> pointid_2_trueid;
170 unordered_set<int> inliers;
172 for (
size_t i = 0; i < true_points.size(); ++i) {
174 v_p->
setId(point_id);
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) {
190 for (
size_t j = 0; j < true_poses.size(); ++j) {
192 cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
194 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
196 if (sam < OUTLIER_RATIO) {
205 optimizer.
vertices().find(j)->second));
218 inliers.insert(point_id);
219 Vector3d diff = v_p->
estimate() - true_points[i];
221 sum_diff2 += diff.dot(diff);
223 pointid_2_trueid.insert(make_pair(point_id, i));
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);
241 structure_only_ba.
calc(points, 10);
245 cout <<
"Performing full BA:" << endl;
248 cout <<
"Point error before optimisation (inliers only): "
249 << sqrt(sum_diff2 / inliers.size()) << endl;
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;
261 cerr <<
"Vertex " << it->first <<
"is not a PointXYZ!" << endl;
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);
268 cout <<
"Point error after optimisation (inliers only): "
269 << sqrt(sum_diff2 / inliers.size()) << endl;