MRPT  2.0.1
test.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 /* ===========================================================================
11  EXAMPLE: bundle_adj_full_demo
12  PURPOSE: Demonstrate "mrpt::vision::bundle_adj_full" with a set of
13  simulated or real data. If the program is called without command
14  line arguments, simulated measurements will be used.
15  To use real data, invoke:
16  bundle_adj_full_demo <feats.txt> <cam_model.cfg>
17 
18  Where <feats.txt> is a "TSequenceFeatureObservations" saved as
19  a text file, and <cam_model.cfg> is a .ini-like file with a
20  section named "CAMERA" loadable by mrpt::img::TCamera.
21 
22  DATE: 20-Aug-2010
23  ===========================================================================
24  */
25 
30 #include <mrpt/math/geometry.h>
34 #include <mrpt/poses/CPose3DQuat.h>
35 #include <mrpt/random.h>
36 #include <mrpt/system/filesystem.h>
38 #include <mrpt/vision/pinhole.h>
39 #include <iostream>
40 
41 using namespace mrpt;
42 using namespace mrpt::gui;
43 using namespace mrpt::math;
44 using namespace mrpt::system;
45 using namespace mrpt::opengl;
46 using namespace mrpt::poses;
47 using namespace mrpt::img;
48 using namespace mrpt::vision;
49 using namespace std;
50 
52 
53 double WORLD_SCALE = 1; // Will change when loading SBA examples
54 
55 // A feedback functor, which is called on each iteration by the optimizer to let
56 // us know on the progress:
58  const size_t cur_iter, const double cur_total_sq_error,
59  const size_t max_iters,
60  const TSequenceFeatureObservations& input_observations,
61  const TFramePosesVec& current_frame_estimate,
62  const TLandmarkLocationsVec& current_landmark_estimate)
63 {
64  const double avr_err =
65  std::sqrt(cur_total_sq_error / input_observations.size());
66  history_avr_err.push_back(std::log(1e-100 + avr_err));
67  if ((cur_iter % 10) == 0)
68  {
69  cout << "[PROGRESS] Iter: " << cur_iter
70  << " avrg err in px: " << avr_err << endl;
71  cout.flush();
72  }
73 }
74 
75 // ------------------------------------------------------
76 // bundle_adj_full_demo
77 // ------------------------------------------------------
79  const TCamera& camera_params, const TSequenceFeatureObservations& allObs,
80  TFramePosesVec& frame_poses, TLandmarkLocationsVec& landmark_points)
81 {
82  cout << "Optimizing " << allObs.size() << " feature observations.\n";
83 
84  TParametersDouble extra_params;
85  // extra_params["verbose"] = 1;
86  extra_params["max_iterations"] = 2000; // 250;
87  // extra_params["num_fix_frames"] = 1;
88  // extra_params["num_fix_points"] = 0;
89  extra_params["robust_kernel"] = 0;
90  extra_params["kernel_param"] = 5.0;
91  extra_params["profiler"] = 1;
92 
94  allObs, camera_params, frame_poses, landmark_points, extra_params,
96 }
97 // ---------------------------------------------------------
98 
100  const TFramePosesVec& poses, const double len, const double lineWidth);
101 
102 // ------------------------------------------------------
103 // MAIN
104 // ------------------------------------------------------
105 int main(int argc, char** argv)
106 {
107  try
108  {
109  // Simulation or real-data? (read at the top of this file):
110  if ((argc != 1 && argc != 3 && argc != 4) ||
111  (argc == 2 && !strcpy(argv[1], "--help")))
112  {
113  cout << "Usage:\n"
114  << argv[0] << " --help -> Shows this help\n"
115  << argv[0] << " -> Simulation\n"
116  << argv[0]
117  << " <feats.txt> <cam_model.cfg> -> Data in MRPT format\n"
118  << argv[0]
119  << " <cams.txt> <points.cfg> <calib.txt> -> SBA format\n";
120  return 1;
121  }
122 
123  // BA data:
124  TCamera camera_params;
126  TFramePosesVec frame_poses;
127  TLandmarkLocationsVec landmark_points;
128 
129  // Only for simulation mode:
130  TFramePosesVec frame_poses_real,
131  frame_poses_noisy; // Ground truth & starting point
132  TLandmarkLocationsVec landmark_points_real,
133  landmark_points_noisy; // Ground truth & starting point
134 
135  if (argc == 1)
136  {
137  random::CRandomGenerator rg(1234);
138 
139  // Simulation
140  // --------------------------
141  // The projective camera model:
142  camera_params.ncols = 800;
143  camera_params.nrows = 600;
144  camera_params.fx(400);
145  camera_params.fy(400);
146  camera_params.cx(400);
147  camera_params.cy(300);
148 
149  // Generate synthetic dataset:
150  // -------------------------------------
151  const size_t nPts = 100; // # of 3D landmarks
152  const double L1 =
153  60; // Draw random poses in the rectangle L1xL2xL3
154  const double L2 = 10;
155  const double L3 = 10;
156  const double max_camera_dist = L1 * 4;
157 
158  const double cameraPathLen = L1 * 1.2;
159  // const double cameraPathEllipRadius1 = L1*2;
160  // const double cameraPathEllipRadius2 = L2*2;
161  // Noise params:
162  const double STD_PX_ERROR = 0.10; // pixels
163 
164  const double STD_PX_ERROR_OUTLIER = 5; // pixels
165  const double PROBABILITY_OUTLIERS = 0; // 0.01;
166 
167  const double STD_PT3D = 0.10; // meters
168  const double STD_CAM_XYZ = 0.05; // meters
169  const double STD_CAM_ANG = 5.0_deg; // degs
170 
171  landmark_points_real.resize(nPts);
172  for (size_t i = 0; i < nPts; i++)
173  {
174  landmark_points_real[i].x = rg.drawUniform(-L1, L1);
175  landmark_points_real[i].y = rg.drawUniform(-L2, L2);
176  landmark_points_real[i].z = rg.drawUniform(-L3, L3);
177  }
178 
179  // const double angStep = M_PI*2.0/40;
180  const double camPosesSteps = 2 * cameraPathLen / 20;
181  frame_poses_real.clear();
182 
183  for (double x = -cameraPathLen; x < cameraPathLen;
184  x += camPosesSteps)
185  {
186  TPose3D p;
187  p.x = x; // cameraPathEllipRadius1 * cos(ang);
188  p.y = 4 * L2; // cameraPathEllipRadius2 * sin(ang);
189  p.z = 0;
190  p.yaw = -90.0_deg -
191  30.0_deg * x / cameraPathLen; // wrapToPi(ang+M_PI);
192  p.pitch = 0;
193  p.roll = 0;
194  // Angles above is for +X pointing to the (0,0,0), but we want
195  // instead +Z pointing there, as typical in camera models:
196  frame_poses_real.push_back(
197  CPose3D(p) + CPose3D(0, 0, 0, -90.0_deg, 0, -90.0_deg));
198  }
199 
200  // Simulate the feature observations:
201  size_t numOutliers = 0;
202  allObs.clear();
203  map<TCameraPoseID, size_t> numViewedFrom;
204  for (size_t i = 0; i < frame_poses_real.size();
205  i++) // for each pose
206  {
207  // predict all landmarks:
208  for (size_t j = 0; j < landmark_points_real.size(); j++)
209  {
210  TPixelCoordf px =
212  false>(
213  camera_params, frame_poses_real[i],
214  landmark_points_real[j]);
215 
216  const bool is_outlier =
217  (rg.drawUniform(0.0, 1.0) < PROBABILITY_OUTLIERS);
218  px.x += rg.drawGaussian1D(
219  0, is_outlier ? STD_PX_ERROR_OUTLIER : STD_PX_ERROR);
220  px.y += rg.drawGaussian1D(
221  0, is_outlier ? STD_PX_ERROR_OUTLIER : STD_PX_ERROR);
222 
223  // Out of image?
224  if (px.x < 0 || px.y < 0 || px.x > camera_params.ncols ||
225  px.y > camera_params.nrows)
226  continue;
227 
228  // Too far?
229  const double dist = math::distance(
230  TPoint3D(frame_poses_real[i].asTPose()),
231  landmark_points_real[j]);
232  if (dist > max_camera_dist) continue;
233 
234  // Ok, accept it:
235  if (is_outlier) numOutliers++;
236  allObs.push_back(TFeatureObservation(j, i, px));
237  numViewedFrom[i]++;
238  }
239  }
240  cout << "Simulated: " << allObs.size()
241  << " observations (of which: " << numOutliers
242  << " are outliers).\n";
243 
244  ASSERT_EQUAL_(numViewedFrom.size(), frame_poses_real.size());
245  // Make sure all poses and all LMs appear at least once!
246  {
247  TSequenceFeatureObservations allObs2 = allObs;
248  std::map<TCameraPoseID, TCameraPoseID> old2new_camIDs;
249  std::map<TLandmarkID, TLandmarkID> old2new_lmIDs;
250  allObs2.compressIDs(&old2new_camIDs, &old2new_lmIDs);
251 
252  ASSERT_EQUAL_(old2new_camIDs.size(), frame_poses_real.size());
254  old2new_lmIDs.size(), landmark_points_real.size());
255  }
256 
257  // Add noise to the data:
258  frame_poses_noisy = frame_poses_real;
259  landmark_points_noisy = landmark_points_real;
260  for (size_t i = 0; i < landmark_points_noisy.size(); i++)
261  landmark_points_noisy[i] += TPoint3D(
262  rg.drawGaussian1D(0, STD_PT3D),
263  rg.drawGaussian1D(0, STD_PT3D),
264  rg.drawGaussian1D(0, STD_PT3D));
265 
266  for (size_t i = 1; i < frame_poses_noisy.size();
267  i++) // DON'T add error to frame[0], the global reference!
268  {
269  CPose3D bef = frame_poses_noisy[i];
270  frame_poses_noisy[i].setFromValues(
271  frame_poses_noisy[i].x() +
272  rg.drawGaussian1D(0, STD_CAM_XYZ),
273  frame_poses_noisy[i].y() +
274  rg.drawGaussian1D(0, STD_CAM_XYZ),
275  frame_poses_noisy[i].z() +
276  rg.drawGaussian1D(0, STD_CAM_XYZ),
277  frame_poses_noisy[i].yaw() +
278  rg.drawGaussian1D(0, STD_CAM_ANG),
279  frame_poses_noisy[i].pitch() +
280  rg.drawGaussian1D(0, STD_CAM_ANG),
281  frame_poses_noisy[i].roll() +
282  rg.drawGaussian1D(0, STD_CAM_ANG));
283  }
284 
285  // Optimize it:
286  frame_poses = frame_poses_noisy;
287  landmark_points = landmark_points_noisy;
288 
289 #if 0
290  vector<std::array<double,2> > resids;
291  const double initial_total_sq_err = mrpt::vision::reprojectionResiduals(allObs,camera_params,frame_poses, landmark_points,resids, false);
292  cout << "Initial avr error in px: " << std::sqrt(initial_total_sq_err/allObs.size()) << endl;
293 #endif
294 
295  // Run Bundle Adjustmen
297  camera_params, allObs, frame_poses, landmark_points);
298 
299  // Evaluate vs. ground truth:
300  double landmarks_total_sq_err = 0;
301  for (size_t i = 0; i < landmark_points.size(); i++)
302  landmarks_total_sq_err += square(
303  landmark_points_real[i].distanceTo(landmark_points[i]));
304 
305  double cam_point_total_sq_err = 0;
306  for (size_t i = 0; i < frame_poses.size(); i++)
307  cam_point_total_sq_err +=
308  square(frame_poses[i].distanceTo(frame_poses_real[i]));
309 
310  cout << "RMSE of recovered landmark positions: "
311  << std::sqrt(landmarks_total_sq_err / landmark_points.size())
312  << endl;
313  cout << "RMSE of recovered camera positions: "
314  << std::sqrt(cam_point_total_sq_err / frame_poses.size())
315  << endl;
316  }
317  else
318  {
319  // Real data
320  // --------------------------
321  if (argc == 3)
322  {
323  const string feats_fil = string(argv[1]);
324  const string cam_fil = string(argv[2]);
325 
326  cout << "Loading observations from: " << feats_fil << "...";
327  cout.flush();
328  allObs.loadFromTextFile(feats_fil);
329  cout << "Done.\n";
330 
331  allObs.decimateCameraFrames(20);
332  allObs.compressIDs();
333 
335  cout << "Loading camera params from: " << cam_fil;
336  mrpt::config::CConfigFile cfgCam(cam_fil);
337  camera_params.loadFromConfigFile("CAMERA", cfgCam);
338  cout << "Done.\n";
339 
340  cout << "Initial gross estimate...";
342  allObs, camera_params, frame_poses, landmark_points);
343  cout << "OK\n";
344  }
345  else
346  {
347  // Load data from 3 files in the same format as used by
348  // "eucsbademo" in the SBA library:
349  const string cam_frames_fil = string(argv[1]);
350  const string obs_fil = string(argv[2]);
351  const string calib_fil = string(argv[3]);
352 
353  {
354  cout << "Loading initial camera frames from: "
355  << cam_frames_fil << "...";
356  cout.flush();
357 
358  mrpt::io::CTextFileLinesParser fil(cam_frames_fil);
359  frame_poses.clear();
360 
361  std::istringstream ss;
362  while (fil.getNextLine(ss))
363  {
364  double q[4], t[3];
365  ss >> q[0] >> q[1] >> q[2] >> q[3] >> t[0] >> t[1] >>
366  t[2];
368  t[0], t[1], t[2],
370  q[0], q[1], q[2], q[3]));
371  // cout << "cam: " << p << endl;
372  frame_poses.push_back(CPose3D(p));
373  }
374 
375  cout << "Done. " << frame_poses.size()
376  << " cam frames loaded\n";
377 
378  frame_poses_noisy = frame_poses; // To draw in 3D the
379  // initial values as well.
380  }
381 
382  {
383  cout << "Loading observations & feature 3D points from: "
384  << obs_fil << "...";
385  cout.flush();
386 
387  mrpt::io::CTextFileLinesParser fil(obs_fil);
388  landmark_points.clear();
389  allObs.clear();
390 
391  std::istringstream ss;
392  while (fil.getNextLine(ss))
393  {
394  // # X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
395  double t[3];
396  size_t N = 0;
397  ss >> t[0] >> t[1] >> t[2] >> N;
398 
399  const TLandmarkID feat_id = landmark_points.size();
400  const TPoint3D pt(t[0], t[1], t[2]);
401  landmark_points.push_back(pt);
402 
403  // Read obs:
404  for (size_t i = 0; i < N; i++)
405  {
406  TCameraPoseID frame_id;
407  TPixelCoordf px;
408  ss >> frame_id >> px.x >> px.y;
409  allObs.push_back(
410  TFeatureObservation(feat_id, frame_id, px));
411  // cout << "feat: " << feat_id << " cam: " <<
412  // frame_id << " px: " << px.x << "," << px.y <<
413  // endl;
414  }
415  }
416 
417  cout << "Done. " << landmark_points.size() << " points, "
418  << allObs.size() << " observations read.\n";
419 
420  landmark_points_real = landmark_points; // To draw in 3D
421  // the initial
422  // values as well.
423  }
424 
425  CMatrixDouble33 cam_pars;
426  cam_pars.loadFromTextFile(calib_fil);
427 
428  // cout << "Calib:\n" << cam_pars << endl;
429 
430  camera_params.fx(cam_pars(0, 0));
431  camera_params.fy(cam_pars(1, 1));
432  camera_params.cx(cam_pars(0, 2));
433  camera_params.cy(cam_pars(1, 2));
434 
435  cout << "camera calib:\n" << camera_params.dumpAsText() << endl;
436 
437  // Change world scale:
438  WORLD_SCALE = 2000;
439  }
440 
441  // Do it:
443  camera_params, allObs, frame_poses, landmark_points);
444  }
445 
446  // Display results in 3D:
447  // -------------------------------
448  gui::CDisplayWindow3D win("Bundle adjustment demo", 800, 600);
449 
450  COpenGLScene::Ptr& scene = win.get3DSceneAndLock();
451 
452  { // Ground plane:
453  auto obj = CGridPlaneXY::Create(-200, 200, -200, 200, 0, 5);
454  obj->setColor(0.7, 0.7, 0.7);
455  scene->insert(obj);
456  }
457 
458  if (!landmark_points_real.empty())
459  { // Feature points: ground truth
460  auto obj = CPointCloud::Create();
461  obj->setPointSize(2);
462  obj->setColor(0, 0, 0);
463  obj->loadFromPointsList(landmark_points_real);
464  obj->setScale(WORLD_SCALE);
465  scene->insert(obj);
466  }
467  if (!landmark_points_noisy.empty())
468  { // Feature points: noisy
469  auto obj = CPointCloud::Create();
470  obj->setPointSize(4);
471  obj->setColor(0.7, 0.2, 0.2, 0);
472  obj->loadFromPointsList(landmark_points_noisy);
473  obj->setScale(WORLD_SCALE);
474  scene->insert(obj);
475  }
476 
477  { // Feature points: estimated
478  auto obj = CPointCloud::Create();
479  obj->setPointSize(3);
480  obj->setColor(0, 0, 1, 1.0);
481  obj->loadFromPointsList(landmark_points);
482  obj->setScale(WORLD_SCALE);
483  scene->insert(obj);
484  }
485 
486  // Camera Frames: estimated
487  scene->insert(framePosesVecVisualize(frame_poses_noisy, 1.0, 1));
488  scene->insert(framePosesVecVisualize(frame_poses_real, 2.0, 1));
489  scene->insert(framePosesVecVisualize(frame_poses, 2.0, 3));
490 
491  win.setCameraZoom(100);
492 
493  win.unlockAccess3DScene();
494  win.repaint();
495 
496  // Also, show history of error:
497  gui::CDisplayWindowPlots winPlot(
498  "Avr log-error with iterations", 500, 200);
499  // winPlot.setPos(0,620);
500  winPlot.plot(history_avr_err, "b.3");
501  winPlot.axis_fit();
502 
503  cout << "Close the 3D window or press a key to exit.\n";
504  win.waitForKey();
505 
506  return 0;
507  }
508  catch (const std::exception& e)
509  {
510  std::cout << "MRPT exception caught: " << e.what() << std::endl;
511  return -1;
512  }
513  catch (...)
514  {
515  printf("Untyped exception!!");
516  return -1;
517  }
518 }
519 
521  const TFramePosesVec& poses, const double len, const double lineWidth)
522 {
524 
525  for (size_t i = 0; i < poses.size(); i++)
526  {
527  CSetOfObjects::Ptr corner =
529  CPose3D p = poses[i];
530  p.x(WORLD_SCALE * p.x());
531  p.y(WORLD_SCALE * p.y());
532  p.z(WORLD_SCALE * p.z());
533  corner->setPose(p);
534  corner->setName(format("%u", (unsigned int)i));
535  corner->enableShowName();
536  obj->insert(corner);
537  }
538  return obj;
539 }
void loadFromTextFile(const std::string &filName)
Load from a text file, in the format described in saveToTextFile.
Definition: types.cpp:52
uint32_t nrows
Definition: TCamera.h:40
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
Create a GUI window and display plots with MATLAB-like interfaces and commands.
uint64_t TLandmarkID
Unique IDs for landmarks.
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:175
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
double roll
Roll coordinate (rotation angle over X coordinate).
Definition: TPose3D.h:38
This class allows loading and storing values and vectors of different types from ".ini" files easily.
double x
X,Y,Z, coords.
Definition: TPose3D.h:32
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:128
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:177
A class for parsing text files, returning each non-empty and non-comment line, along its line number...
One feature observation entry, used within sequences with TSequenceFeatureObservations.
A pair (x,y) of pixel coordinates (subpixel resolution).
Definition: TPixelCoord.h:18
STL namespace.
static Ptr Create(Args &&... args)
Definition: CSetOfObjects.h:28
void ba_initial_estimate(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::img::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points)
Fills the frames & landmark points maps with an initial gross estimate from the sequence observations...
A thred-safe pseudo random number generator, based on an internal MT19937 randomness generator...
double yaw
Yaw coordinate (rotation angle over Z axis).
Definition: TPose3D.h:34
char * strcpy(char *dest, size_t destSize, const char *source) noexcept
An OS-independent version of strcpy.
void push_back(const T &val)
A complete sequence of observations of features from different camera frames (poses).
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
std::vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
This base provides a set of functions for maths stuff.
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:173
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
Definition: exceptions.h:137
void my_BundleAdjustmentFeedbackFunctor(const size_t cur_iter, const double cur_total_sq_error, const size_t max_iters, const TSequenceFeatureObservations &input_observations, const TFramePosesVec &current_frame_estimate, const TLandmarkLocationsVec &current_landmark_estimate)
double WORLD_SCALE
Classes for computer vision, detectors, features, etc.
Definition: CDifodo.h:17
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:26
TPoint3D_< double > TPoint3D
Lightweight 3D point.
Definition: TPoint3D.h:268
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:143
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:45
double reprojectionResiduals(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::img::TCamera &camera_params, const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vision::TLandmarkLocationsVec &landmark_points, std::vector< std::array< double, 2 >> &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0, std::vector< double > *out_kernel_1st_deriv=nullptr)
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...
mrpt::gui::CDisplayWindow3D::Ptr win
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double pitch
Pitch coordinate (rotation angle over Y axis).
Definition: TPose3D.h:36
return_t square(const num_t x)
Inline function for the square of a number.
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:171
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
const char * argv[]
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::img::TPixelCoordf projectPoint_no_distortion(const mrpt::img::TCamera &cam_params, const mrpt::poses::CPose3D &F, const mrpt::math::TPoint3D &P)
Project a single 3D point with global coordinates P into a camera at pose F, without distortion param...
Definition: pinhole.h:63
CSetOfObjects::Ptr CornerXYZSimple(float scale=1.0, float lineWidth=1.0)
Returns three arrows representing a X,Y,Z 3D corner (just thick lines instead of complex arrows for f...
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
Definition: CPose3D.cpp:265
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Definition: TPose3D.h:24
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
void bundle_adj_full_demo(const TCamera &camera_params, const TSequenceFeatureObservations &allObs, TFramePosesVec &frame_poses, TLandmarkLocationsVec &landmark_points)
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
const int argc
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:44
double bundle_adj_full(const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::img::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::system::TParametersDouble &extra_params=mrpt::system::TParametersDouble(), const mrpt::vision::TBundleAdjustmentFeedbackFunctor user_feedback=mrpt::vision::TBundleAdjustmentFeedbackFunctor())
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
CVectorDouble history_avr_err
uint32_t ncols
Camera resolution.
Definition: TCamera.h:40
void compressIDs(std::map< TCameraPoseID, TCameraPoseID > *old2new_camIDs=nullptr, std::map< TLandmarkID, TLandmarkID > *old2new_lmIDs=nullptr)
Rearrange frame and feature IDs such as they start at 0 and there are no gaps.
Definition: types.cpp:198
mrpt::opengl::CSetOfObjects::Ptr framePosesVecVisualize(const TFramePosesVec &poses, const double len, const double lineWidth)
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
Definition: geometry.cpp:1807
void decimateCameraFrames(const size_t decimate_ratio)
Remove all but one out of decimate_ratio camera frame IDs from the list (eg: from N camera pose IDs a...
Definition: types.cpp:164
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.
void loadFromTextFile(std::istream &f)
Loads a vector/matrix from a text file, compatible with MATLAB text format.



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020