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 
18 #include <mrpt/slam/CICP.h>
19 #include <mrpt/system/filesystem.h>
20 
21 #if MRPT_HAS_NANOGUI
22 
23 using namespace mrpt;
24 using namespace mrpt::vision;
25 using namespace mrpt::hwdrivers;
26 using namespace mrpt::img;
27 using namespace mrpt::poses;
28 using namespace mrpt::math;
29 using namespace mrpt::gui;
30 using namespace mrpt::tfest;
31 using namespace mrpt::obs;
32 using namespace mrpt::maps;
33 using namespace mrpt::slam;
34 using namespace mrpt::system;
35 using namespace mrpt::opengl;
36 using namespace std;
37 
38 const double KEYFRAMES_MIN_DISTANCE = 0.50; // meters
39 const double KEYFRAMES_MIN_ANG = 20.0_deg;
40 
41 // Thread for grabbing: Do this is another thread so we divide rendering and
42 // grabbing
43 // and exploit multicore CPUs.
44 struct TThreadParam
45 {
46  TThreadParam() = default;
47  std::atomic_bool quit{false};
48  std::atomic<double> Hz{0};
49 
51 };
52 
54 {
55  try
56  {
58 
59  const std::string str =
60  "[CONFIG]\n"
61  "grabber_type=myntd\n";
62 
64  cam.loadConfig(cfg, "CONFIG");
65 
66  // Open:
67  cout << "Calling initialize()...";
68  cam.initialize();
69  cout << "OK\n";
70 
71  CTicTac tictac;
72  int nImgs = 0;
73 
74  while (!p.quit)
75  {
76  // Grab new observation from the camera:
77 
78  cam.doProcess();
79 
81  cam.getObservations(obss);
82 
83  if (obss.empty())
84  {
85  std::this_thread::sleep_for(10ms);
86  continue;
87  }
88 
90  obss.begin()->second);
91 
92  if (!obs) continue;
93 
94  std::atomic_store(&p.new_obs, obs);
95 
96  nImgs++;
97  if (nImgs > 10)
98  {
99  p.Hz = nImgs / tictac.Tac();
100  nImgs = 0;
101  tictac.Tic();
102  }
103  }
104  }
105  catch (const std::exception& e)
106  {
107  cout << "Exception in Kinect thread: " << mrpt::exception_to_str(e)
108  << endl;
109  p.quit = true;
110  }
111 }
112 
113 // ------------------------------------------------------
114 // Test_3DCamICP
115 // ------------------------------------------------------
116 void Test_3DCamICP()
117 {
118  // Launch grabbing thread:
119  // --------------------------------------------------------
120  TThreadParam thrPar;
121  std::thread thHandle = std::thread(thread_grabbing, std::ref(thrPar));
122 
123  // Wait until data stream starts so we can say for sure the sensor has been
124  // initialized OK:
125  cout << "Waiting for sensor initialization...\n";
126  do
127  {
128  CObservation3DRangeScan::Ptr possiblyNewObs =
129  std::atomic_load(&thrPar.new_obs);
130  if (possiblyNewObs && possiblyNewObs->timestamp != INVALID_TIMESTAMP)
131  break;
132  else
133  std::this_thread::sleep_for(10ms);
134  } while (!thrPar.quit);
135 
136  // Check error condition:
137  if (thrPar.quit) return;
138 
139  // Create window and prepare OpenGL object in the scene:
140  // --------------------------------------------------------
141  nanogui::init();
142 
143  mrpt::gui::CDisplayWindowGUI win("3D camera ICP demo", 1000, 800);
144 
145  win.camera().setAzimuthDegrees(140.0f);
146  win.camera().setElevationDegrees(20.0f);
147  win.camera().setZoomDistance(8.0f);
148  win.camera().setCameraFOV(50.0f);
149  win.camera().setCameraPointing(2.5, 0, 0);
150 
151  // Aux structure to share UI data between threads.
152  struct ui_data_t
153  {
154  // In the 2D image:
155  std::atomic_bool SHOW_FEAT_IDS = true;
156  std::atomic_bool SHOW_RESPONSES = true;
157 
158  std::atomic_bool hasToReset = false;
159 
160  unsigned int icpDecimation = 16;
161 
162  std::mutex strStatuses_mtx;
163  std::array<std::string, 4> strStatuses;
164 
166  std::mutex* viewInt_mtx = nullptr;
167 
168  // Set defaults:
169  ui_data_t() = default;
170  };
171 
172  ui_data_t ui_data;
173 
174  // The main function to be run in parallel to check for new observations,
175  // update the GL objects, etc.
176  auto lambdaUpdateThread = [&win, &thrPar, &ui_data]() {
178  auto gl_keyframes = mrpt::opengl::CSetOfObjects::Create();
179  auto gl_points_map = mrpt::opengl::CPointCloudColoured::Create();
180  auto gl_cur_cam_corner = mrpt::opengl::stock_objects::CornerXYZ(0.4f);
181  gl_points->setPointSize(1.25f);
182  gl_points_map->setPointSize(1.5f);
183 
184  {
185  auto scene = mrpt::opengl::COpenGLScene::Create();
186 
187  // Create the Opengl object for the point cloud:
188  scene->insert(gl_points_map);
189  scene->insert(gl_points);
190  scene->insert(gl_keyframes);
191  scene->insert(mrpt::opengl::CGridPlaneXY::Create());
192 
193  scene->insert(gl_cur_cam_corner);
194 
195  win.background_scene_mtx.lock();
196  win.background_scene = std::move(scene);
197  win.background_scene_mtx.unlock();
198  }
199 
200  // The 6D path of the Kinect camera.
201  std::vector<TPose3D> camera_key_frames_path;
202 
203  // wrt last pose in "camera_key_frames_path"
204  CPose3D currentCamPose_wrt_last;
205 
206  unsigned int step_num = 0;
207 
208  // Need to update gl_keyframes from camera_key_frames_path??
209  bool gl_keyframes_must_refresh = true;
210 
212  CColouredPointsMap::Ptr cur_points, prev_points;
213 
214  // Global points map:
215  CColouredPointsMap globalPtsMap;
216 
217  globalPtsMap.colorScheme.scheme =
218  CColouredPointsMap::cmFromIntensityImage; // Take points color from
219  // RGB+D observations
220 
221  mrpt::slam::CICP icp;
222  icp.options.maxIterations = 80;
223  icp.options.thresholdDist = 0.10; // [m]
224  icp.options.thresholdAng = 1.0_deg;
225  icp.options.ALFA = 0.001; // wun with only 1 set of thresholds
226 
227  mrpt::poses::CPose3D lastIcpRelPose;
228 
229  // Should we exit?
230  while (!thrPar.quit)
231  {
232  std::this_thread::sleep_for(5ms);
233 
234  CObservation3DRangeScan::Ptr possiblyNewObs =
235  std::atomic_load(&thrPar.new_obs);
236  if (!possiblyNewObs ||
237  possiblyNewObs->timestamp == INVALID_TIMESTAMP ||
238  (cur_obs && possiblyNewObs->timestamp == cur_obs->timestamp))
239  continue; // No new data
240 
241  // It IS a new observation:
242  cur_obs = possiblyNewObs;
243 
244  // Unproject 3D points:
245  if (!cur_points)
246  cur_points = CColouredPointsMap::Create();
247  else
248  cur_points->clear();
249 
250  // Also, unproject all for viz:
252  pp.decimation = ui_data.icpDecimation;
253 
254  cur_obs->unprojectInto(*cur_points, pp);
255 
256  // ICP -------------------------------------------
257  // The grabbed image:
258  CImage theImg = cur_obs->intensityImage;
259 
260  CPose3DPDF::Ptr icp_out;
262 
263  if (!prev_points)
264  {
265  // Make a deep copy:
266  prev_points = CColouredPointsMap::Create(*cur_points);
267  }
268 
269  icp_out = icp.Align3D(
270  prev_points.get(), cur_points.get(), lastIcpRelPose, icp_res);
271 
272  // Load local points map from 3D points + color:
273  cur_obs->unprojectInto(*gl_points);
274 
275  // Estimate our current camera pose from feature2feature matching:
276  // --------------------------------------------------------------------
277  if (icp_out && icp_res.nIterations > 0)
278  {
279  const CPose3D relativePose = icp_out->getMeanVal();
280  lastIcpRelPose = relativePose;
281 
282  ui_data.strStatuses_mtx.lock();
283  ui_data.strStatuses[0] = mrpt::format(
284  "ICP: %d iters, goodness: %.02f%%",
285  int(icp_res.nIterations), icp_res.goodness * 100.0f),
286 
287  ui_data.strStatuses[1] =
288  std::string("rel.pose:") + relativePose.asString();
289  ui_data.strStatuses[2] =
290  string(icp_res.goodness < 0.3 ? "LOST! Press restart" : "");
291  ui_data.strStatuses_mtx.unlock();
292 
293  if (icp_res.goodness > 0.65)
294  {
295  // Seems a good match:
296  if ((relativePose.norm() > KEYFRAMES_MIN_DISTANCE ||
297  std::abs(relativePose.yaw()) > KEYFRAMES_MIN_ANG ||
298  std::abs(relativePose.pitch()) > KEYFRAMES_MIN_ANG ||
299  std::abs(relativePose.roll()) > KEYFRAMES_MIN_ANG))
300  {
301  // Accept this as a new key-frame pose ------------
302  // Append new global pose of this key-frame:
303 
304  const CPose3D new_keyframe_global =
305  CPose3D(*camera_key_frames_path.rbegin()) +
306  relativePose;
307 
308  camera_key_frames_path.push_back(
309  new_keyframe_global.asTPose());
310 
311  gl_keyframes_must_refresh = true;
312  // It's (0,0,0) since the last
313  // key-frame is the current pose!
314  currentCamPose_wrt_last = CPose3D();
315 
316  cout << "Adding new key-frame: pose="
317  << new_keyframe_global << endl;
318 
319  // Update global map: append another map at a given
320  // position:
321  globalPtsMap.insertAnotherMap(
322  cur_points.get(), new_keyframe_global);
323 
324  win.background_scene_mtx.lock();
325  gl_points_map->loadFromPointsMap(&globalPtsMap);
326  win.background_scene_mtx.unlock();
327 
328  prev_points = std::move(cur_points); // new KF
329  }
330  else
331  {
332  currentCamPose_wrt_last = relativePose;
333  // cout << "cur pose: " << currentCamPose_wrt_last
334  // << endl;
335  }
336  }
337  }
338 
339  if (camera_key_frames_path.empty())
340  {
341  // First iteration:
342  camera_key_frames_path.clear();
343  camera_key_frames_path.emplace_back(0, 0, 0, 0, 0, 0);
344  gl_keyframes_must_refresh = true;
345 
346  // Update global map:
347  globalPtsMap.clear();
348  globalPtsMap.insertObservation(*cur_obs);
349 
350  win.background_scene_mtx.lock();
351  gl_points_map->loadFromPointsMap(&globalPtsMap);
352  win.background_scene_mtx.unlock();
353  }
354 
355  // Update visualization ---------------------------------------
356 
357  // Show 3D points & current visible feats, at the current camera 3D
358  // pose "currentCamPose_wrt_last"
359  // ---------------------------------------------------------------------
360  {
361  const CPose3D curGlobalPose =
362  CPose3D(*camera_key_frames_path.rbegin()) +
363  currentCamPose_wrt_last;
364  win.background_scene_mtx.lock();
365  // All 3D points:
366  cur_obs->unprojectInto(*gl_points);
367  gl_points->setPose(curGlobalPose);
368 
369  gl_cur_cam_corner->setPose(curGlobalPose);
370 
371  win.background_scene_mtx.unlock();
372  }
373 
374  if (gl_keyframes_must_refresh)
375  {
376  gl_keyframes_must_refresh = false;
377  // cout << "Updating gl_keyframes with " <<
378  // camera_key_frames_path.size() << " frames.\n";
379 
380  win.background_scene_mtx.lock();
381  gl_keyframes->clear();
382  for (const auto& i : camera_key_frames_path)
383  {
384  CSetOfObjects::Ptr obj =
386  obj->setPose(i);
387  gl_keyframes->insert(obj);
388  }
389  win.background_scene_mtx.unlock();
390  }
391 
392  ui_data.strStatuses_mtx.lock();
393  ui_data.strStatuses[3] =
394  format("Frames: %.02f Hz", std::atomic_load(&thrPar.Hz));
395  ui_data.strStatuses_mtx.unlock();
396 
397  step_num++;
398 
399  // end update visualization:
400 
401  if (ui_data.hasToReset)
402  {
403  ui_data.hasToReset = false;
404 
405  cur_points.reset();
406  prev_points.reset();
407  lastIcpRelPose = CPose3D();
408  camera_key_frames_path.clear();
409  gl_keyframes_must_refresh = true;
410  globalPtsMap.clear();
411  win.background_scene_mtx.lock();
412  gl_points_map->loadFromPointsMap(&globalPtsMap);
413  win.background_scene_mtx.unlock();
414  }
415 
416  // Show intensity image
417  ui_data.viewInt_mtx->lock();
418  ui_data.viewInt->setImageView(std::move(theImg));
419  ui_data.viewInt_mtx->unlock();
420  }
421  }; // end lambdaUpdateThread
422 
423  std::thread thWorker = std::thread(lambdaUpdateThread);
424 
425  // Add UI controls:
426  std::array<nanogui::TextBox*, 4> lbStatuses = {nullptr, nullptr, nullptr,
427  nullptr};
428  mrpt::gui::MRPT2NanoguiGLCanvas* glCanvasRGBView = nullptr;
429  nanogui::Window* subWin2 = nullptr;
430 
431  {
432  auto subWin = new nanogui::Window(&win, "Control");
433  subWin->setLayout(new nanogui::GroupLayout());
434  subWin->setFixedWidth(400);
435 
436  subWin->add<nanogui::Label>("Visualization", "sans-bold");
437  {
438  auto cb = subWin->add<nanogui::CheckBox>("Show feature IDs");
439  cb->setCallback(
440  [&ui_data](bool checked) { ui_data.SHOW_FEAT_IDS = checked; });
441  cb->setChecked(true);
442  }
443 
444  {
445  auto cb = subWin->add<nanogui::CheckBox>("Show keypoint responses");
446  cb->setCallback(
447  [&ui_data](bool checked) { ui_data.SHOW_RESPONSES = checked; });
448  cb->setChecked(true);
449  }
450 
451  for (unsigned int i = 0; i < lbStatuses.size(); i++)
452  lbStatuses[i] = subWin->add<nanogui::TextBox>("");
453 
454  subWin->add<nanogui::Label>("RGB window size");
455  {
456  auto cmb = subWin->add<nanogui::ComboBox>(std::vector<std::string>(
457  {"Hidden", "200px", "400px", "800px", "1000px"}));
458  cmb->setSelectedIndex(2);
459  cmb->setCallback([&](int sel) {
460  subWin2->setVisible(sel != 0);
461 
462  switch (sel)
463  {
464  case 0:
465  break;
466  case 1:
467  glCanvasRGBView->setFixedWidth(200);
468  break;
469  case 2:
470  glCanvasRGBView->setFixedWidth(400);
471  break;
472  case 3:
473  glCanvasRGBView->setFixedWidth(800);
474  break;
475  case 4:
476  glCanvasRGBView->setFixedWidth(1000);
477  break;
478  };
479  win.performLayout();
480  });
481  }
482 
483  {
484  nanogui::TextBox* slVal =
485  subWin->add<nanogui::TextBox>("Point cloud decimation: 8");
486  nanogui::Slider* sl = subWin->add<nanogui::Slider>();
487 
488  sl->setRange({2, 4});
489  sl->setValue(3);
490  sl->setCallback([&ui_data, slVal](float v) {
491  const unsigned int decim =
492  mrpt::round(std::pow(2.0, mrpt::round(v)));
493  ui_data.icpDecimation = decim;
494  auto s = std::string("Point cloud decimation: ") +
495  std::to_string(ui_data.icpDecimation);
496  slVal->setValue(s);
497  });
498  }
499 
500  subWin->add<nanogui::Label>("Actions", "sans-bold");
501 
502  {
503  auto btn =
504  subWin->add<nanogui::Button>("Reset", ENTYPO_ICON_BACK_IN_TIME);
505  btn->setCallback([&]() { ui_data.hasToReset = true; });
506  }
507 
508  {
509  auto btn =
510  subWin->add<nanogui::Button>("Quit", ENTYPO_ICON_ARROW_LEFT);
511  btn->setCallback([&]() { win.setVisible(false); });
512  }
513  }
514 
515  {
516  subWin2 = new nanogui::Window(&win, "Visible channel");
517  subWin2->setLayout(new nanogui::BoxLayout(
518  nanogui::Orientation::Horizontal, nanogui::Alignment::Fill));
519 
520  glCanvasRGBView = subWin2->add<mrpt::gui::MRPT2NanoguiGLCanvas>();
521  glCanvasRGBView->setFixedWidth(600);
522 
523  // Create the Opengl objects for the planar images each in a
524  // separate viewport:
525 
526  glCanvasRGBView->scene = mrpt::opengl::COpenGLScene::Create();
527  ui_data.viewInt = glCanvasRGBView->scene->getViewport();
528  ui_data.viewInt_mtx = &glCanvasRGBView->scene_mtx;
529 
530  subWin2->setPosition({10, 500});
531  }
532 
533  win.performLayout();
534 
535  // Set loop hook to update text messages:
536  win.setLoopCallback([&lbStatuses, &ui_data]() {
537  ui_data.strStatuses_mtx.lock();
538  for (unsigned int i = 0; i < lbStatuses.size(); i++)
539  lbStatuses[i]->setValue(ui_data.strStatuses[i]);
540  ui_data.strStatuses_mtx.unlock();
541  });
542 
543  // Update view and process events:
544  win.drawAll();
545  win.setVisible(true);
546  nanogui::mainloop();
547 
548  nanogui::shutdown();
549 
550  cout << "Waiting for grabbing thread to exit...\n";
551  thrPar.quit = true;
552  thHandle.join();
553  thWorker.join();
554  cout << "Bye!\n";
555 }
556 
557 #endif // MRPT_HAS_NANOGUI
558 
559 int main(int argc, char** argv)
560 {
561  try
562  {
563 #if MRPT_HAS_NANOGUI
564  Test_3DCamICP();
565 
566  std::this_thread::sleep_for(50ms);
567  return 0;
568 #else
569  THROW_EXCEPTION("This program requires MRPT compiled with NANOGUI");
570 #endif
571  }
572  catch (const std::exception& e)
573  {
574  std::cout << "EXCEPCION: " << mrpt::exception_to_str(e) << std::endl;
575  return -1;
576  }
577 }
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:30
mrpt::math::TPose3D asTPose() const
Definition: CPose3D.cpp:759
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:86
This class implements a config file-like interface over a memory-stored string list.
void insertAnotherMap(const CPointsMap *otherMap, const mrpt::poses::CPose3D &otherPose)
Insert the contents of another map into this one with some geometric transformation, without fusing close points.
const double KEYFRAMES_MIN_ANG
static Ptr Create(Args &&... args)
std::string to_string(T v)
Just like std::to_string(), but with an overloaded version for std::string arguments.
Definition: format.h:36
uint8_t decimation
(Default:1) If !=1, split the range image in blocks of DxD (D=decimation), and only generates one poi...
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Definition: CICP.h:64
A high-performance stopwatch, with typical resolution of nanoseconds.
Contains classes for various device interfaces.
void getObservations(TListObservations &lstObjects)
Returns a list of enqueued objects, emptying it (thread-safe).
double pitch() const
Get the PITCH angle (in radians)
Definition: CPose3D.h:552
double yaw() const
Get the YAW angle (in radians)
Definition: CPose3D.h:546
void doProcess() override
This method will be invoked at a minimum rate of "process_rate" (Hz)
unsigned int nIterations
The number of executed iterations until convergence.
Definition: CICP.h:196
STL namespace.
static Ptr Create(Args &&... args)
Definition: CSetOfObjects.h:28
TConfigParams options
The options employed by the ICP align.
Definition: CICP.h:180
TColourOptions colorScheme
The options employed when inserting laser scans in the map.
volatile bool quit
In/Out variable: Forces the thread to exit or indicates an error in the thread that caused it to end...
This base provides a set of functions for maths stuff.
The central class for camera grabbers in MRPT, implementing the "generic sensor" interface.
unsigned int maxIterations
Maximum number of iterations to run.
Definition: CICP.h:101
This namespace contains representation of robot actions and observations.
Classes for computer vision, detectors, features, etc.
Definition: CDifodo.h:17
double goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
Definition: CICP.h:200
void loadConfig(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensor...
A map of 2D/3D points with individual colours (RGB).
double norm() const
Returns the euclidean norm of vector: .
Definition: CPoseOrPoint.h:256
mrpt::gui::CDisplayWindow3D::Ptr win
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
Definition: CPose3D.h:558
An extension of nanogui::GLCanvas to render MRPT OpenGL scenes.
void asString(std::string &s) const
Returns a human-readable textual representation of the object (eg: "[x y z yaw pitch roll]"...
Definition: CPose3D.h:618
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
const char * argv[]
void initialize() override
Tries to open the camera, after setting all the parameters with a call to loadConfig.
std::multimap< mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr > TListObservations
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
double ALFA
The scale factor for thresholds every time convergence is achieved.
Definition: CICP.h:117
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
mrpt::poses::CPose3DPDF::Ptr Align3D(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3D &grossEst, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt)
void thread_grabbing(TThreadParam &p)
Used in CObservation3DRangeScan::unprojectInto()
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...
mrpt::opengl::COpenGLScene::Ptr scene
The scene to render in this control.
The ICP algorithm return information.
Definition: CICP.h:190
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
std::string exception_to_str(const std::exception &e)
Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THR...
Definition: exceptions.cpp:59
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
Definition: CObject.h:356
const double KEYFRAMES_MIN_DISTANCE
static Ptr Create(Args &&... args)
Definition: COpenGLScene.h:58
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
const int argc
void Test_3DCamICP()
CObservation3DRangeScan::Ptr new_obs
RGB+D (+ optionally, 3D point cloud)
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:75
double thresholdDist
Initial threshold distance for two points to become a correspondence.
Definition: CICP.h:114
Functions for estimating the optimal transformation between two frames of references given measuremen...
static Ptr Create(Args &&... args)
Definition: CGridPlaneXY.h:31
A window with powerful GUI capabilities, via the nanogui library.
volatile double Hz
Out variable: Approx.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
bool insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr)
Insert the observation information into this map.
Definition: CMetricMap.cpp:93
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:148
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:24



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