78 {
79 if (argc < 2) {
80 cout << endl;
81 cout << "Please type: " << endl;
82 cout
83 << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [SCHUR-TRICK]"
84 << endl;
85 cout << endl;
86 cout << "PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
87 cout << "OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
88 << endl;
89 cout << "ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
90 << endl;
91 cout << "SCHUR-TRICK: Use Schur-complement trick (0 or 1; default: 0==true)"
92 << endl;
93 cout << endl;
94 cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
95 "1==true."
96 << endl;
97 cout << endl;
98 exit(0);
99 }
100
101 double PIXEL_NOISE = atof(argv[1]);
102
103 double OUTLIER_RATIO = 0.0;
104 if (argc > 2) {
105 OUTLIER_RATIO = atof(argv[2]);
106 }
107
108 bool ROBUST_KERNEL = false;
109 if (argc > 3) {
110 ROBUST_KERNEL = atoi(argv[3]) != 0;
111 }
112
113 bool SCHUR_TRICK = true;
114 if (argc > 4) {
115 SCHUR_TRICK = atoi(argv[4]) != 0;
116 }
117
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;
122
125
127 if (SCHUR_TRICK) {
128#ifdef G2O_HAVE_CHOLMOD
129 using LinearSolver =
131#else
132 using LinearSolver =
134#endif
136 std::make_unique<g2o::BlockSolver_6_3>(
137 std::make_unique<LinearSolver>()));
138 } else {
139#ifdef G2O_HAVE_CHOLMOD
140 using LinearSolver =
142#else
143 using LinearSolver =
145#endif
147 std::make_unique<g2o::BlockSolverX>(std::make_unique<LinearSolver>()));
148 }
149
151
152 vector<Vector3d> true_points;
153 for (size_t i = 0; i < 500; ++i) {
154 true_points.push_back(
158 }
159
160 double focal_length = 1000.;
161 Vector2d principal_point(320., 240.);
162
163 vector<g2o::SE3Quat, aligned_allocator<g2o::SE3Quat>> true_poses;
164
167 cam_params->
setId(0);
168
170 assert(false);
171 }
172
173 int vertex_id = 0;
174 for (size_t i = 0; i < 15; ++i) {
175 Vector3d trans(i * 0.04 - 1., 0, 0);
176 Eigen::Quaterniond q;
177 q.setIdentity();
180 v_se3->
setId(vertex_id);
182
183 if (i < 2) {
185 }
186
188 true_poses.push_back(T_me_from_world);
189 vertex_id++;
190 }
191 int point_id = vertex_id;
192 int point_num = 0;
193 double sum_diff2 = 0;
194
195 cout << endl;
196 unordered_map<int, int> pointid_2_trueid;
197 unordered_map<int, int> pointid_2_anchorid;
198 unordered_set<int> inliers;
199
200 for (size_t i = 0; i < true_points.size(); ++i) {
202 int num_obs = 0;
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) {
206 ++num_obs;
207 }
208 }
209
210 if (num_obs >= 2) {
211 int anchor_frame_id = -1;
212 bool inlier = true;
213 for (size_t j = 0; j < true_poses.size(); ++j) {
214 Vector2d z =
215 cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
216
217 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
218 if (anchor_frame_id == -1) {
219 anchor_frame_id = j;
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);
223 if (SCHUR_TRICK) {
225 }
226 Vector3d point_w =
230
231 Vector3d point_anchor = T_anchor_from_world * point_w;
234 }
235
237 if (sam < OUTLIER_RATIO) {
239 inlier = false;
240 }
244
248 optimizer.
vertices().find(j)->second));
251 optimizer.
vertices().find(anchor_frame_id)->second));
252
255
256 if (ROBUST_KERNEL) {
259 }
260
263 }
264 }
265 if (inlier) {
266 inliers.insert(point_id);
267 Vector3d diff = true_poses[anchor_frame_id].inverse() *
269 true_points[i];
270 sum_diff2 += diff.dot(diff);
271 }
272 pointid_2_trueid.insert(make_pair(point_id, i));
273 ++point_id;
274 ++point_num;
275 }
276 }
277 cout << endl;
280 cout << endl;
281 cout << "Performing full BA:" << endl;
282
284
285 cout << endl;
286 cout << "Point error before optimisation (inliers only): "
287 <<
sqrt(sum_diff2 / point_num) << endl;
288 point_num = 0;
289 sum_diff2 = 0;
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;
296 exit(-1);
297 }
299 if (v_p == 0) {
300 cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
301 exit(-1);
302 }
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;
307 exit(-1);
308 }
311 if (v_anchor == 0) {
312 cerr << "Vertex " << it->second << "is not a SE3Expmap!" << endl;
313 exit(-1);
314 }
315 Vector3d diff =
317 true_points[it->second];
318 if (inliers.find(it->first) == inliers.end()) continue;
319 sum_diff2 += diff.dot(diff);
320 ++point_num;
321 }
322 cout << "Point error after optimisation (inliers only): "
323 <<
sqrt(sum_diff2 / point_num) << endl;
324 cout << endl;
325}
Vector3d invert_depth(const Vector3d &x)
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
virtual void resize(size_t size)
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
basic solver for Ax = b which has to reimplemented for different linear algebra libraries
linear solver which uses the sparse Cholesky solver from Eigen
void setRobustKernel(RobustKernel *ptr)
bool setParameterId(int argNum, int paramId)
A general case Vertex for optimization.
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
Implementation of the Levenberg Algorithm.
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)
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)
virtual bool addEdge(HyperGraph::Edge *e)
bool addParameter(Parameter *p)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)