78int main(
int argc,
const char* argv[]) {
81 cout <<
"Please type: " << endl;
83 <<
"ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [SCHUR-TRICK]"
86 cout <<
"PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
87 cout <<
"OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
89 cout <<
"ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
91 cout <<
"SCHUR-TRICK: Use Schur-complement trick (0 or 1; default: 0==true)"
94 cout <<
"Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
101 double PIXEL_NOISE = atof(argv[1]);
103 double OUTLIER_RATIO = 0.0;
105 OUTLIER_RATIO = atof(argv[2]);
108 bool ROBUST_KERNEL =
false;
110 ROBUST_KERNEL = atoi(argv[3]) != 0;
113 bool SCHUR_TRICK =
true;
115 SCHUR_TRICK = atoi(argv[4]) != 0;
118 cout <<
"PIXEL_NOISE: " << PIXEL_NOISE << endl;
119 cout <<
"OUTLIER_RATIO: " << OUTLIER_RATIO << endl;
120 cout <<
"ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
121 cout <<
"SCHUR-TRICK: " << SCHUR_TRICK << endl;
128#ifdef G2O_HAVE_CHOLMOD
136 std::make_unique<g2o::BlockSolver_6_3>(
137 std::make_unique<LinearSolver>()));
139#ifdef G2O_HAVE_CHOLMOD
147 std::make_unique<g2o::BlockSolverX>(std::make_unique<LinearSolver>()));
152 vector<Vector3d> true_points;
153 for (
size_t i = 0; i < 500; ++i) {
154 true_points.push_back(
160 double focal_length = 1000.;
161 Vector2d principal_point(320., 240.);
163 vector<g2o::SE3Quat, aligned_allocator<g2o::SE3Quat>> true_poses;
167 cam_params->
setId(0);
174 for (
size_t i = 0; i < 15; ++i) {
175 Vector3d trans(i * 0.04 - 1., 0, 0);
176 Eigen::Quaterniond q;
180 v_se3->
setId(vertex_id);
188 true_poses.push_back(T_me_from_world);
191 int point_id = vertex_id;
193 double sum_diff2 = 0;
196 unordered_map<int, int> pointid_2_trueid;
197 unordered_map<int, int> pointid_2_anchorid;
198 unordered_set<int> inliers;
200 for (
size_t i = 0; i < true_points.size(); ++i) {
203 for (
size_t j = 0; j < true_poses.size(); ++j) {
204 Vector2d z = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
205 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
211 int anchor_frame_id = -1;
213 for (
size_t j = 0; j < true_poses.size(); ++j) {
215 cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
217 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
218 if (anchor_frame_id == -1) {
220 pointid_2_anchorid.insert(make_pair(point_id, anchor_frame_id));
221 g2o::SE3Quat T_anchor_from_world = true_poses[anchor_frame_id];
222 v_p->
setId(point_id);
231 Vector3d point_anchor = T_anchor_from_world * point_w;
237 if (sam < OUTLIER_RATIO) {
248 optimizer.
vertices().find(j)->second));
251 optimizer.
vertices().find(anchor_frame_id)->second));
266 inliers.insert(point_id);
267 Vector3d diff = true_poses[anchor_frame_id].inverse() *
270 sum_diff2 += diff.dot(diff);
272 pointid_2_trueid.insert(make_pair(point_id, i));
281 cout <<
"Performing full BA:" << endl;
286 cout <<
"Point error before optimisation (inliers only): "
287 << sqrt(sum_diff2 / point_num) << endl;
290 for (unordered_map<int, int>::iterator it = pointid_2_trueid.begin();
291 it != pointid_2_trueid.end(); ++it) {
292 g2o::HyperGraph::VertexIDMap::iterator v_it =
293 optimizer.
vertices().find(it->first);
294 if (v_it == optimizer.
vertices().end()) {
295 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
300 cerr <<
"Vertex " << it->first <<
"is not a PointXYZ!" << endl;
303 int anchorframe_id = pointid_2_anchorid.find(it->first)->second;
304 v_it = optimizer.
vertices().find(anchorframe_id);
305 if (v_it == optimizer.
vertices().end()) {
306 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
312 cerr <<
"Vertex " << it->second <<
"is not a SE3Expmap!" << endl;
317 true_points[it->second];
318 if (inliers.find(it->first) == inliers.end())
continue;
319 sum_diff2 += diff.dot(diff);
322 cout <<
"Point error after optimisation (inliers only): "
323 << sqrt(sum_diff2 / point_num) << endl;